diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index 52989b4ac8ed8..c673786b9a143 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -107,7 +107,8 @@ void GCS_MAVLINK_Sub::send_scaled_pressure3() AP_HAL::millis(), 0, 0, - sub.celsius.temperature() * 100); + sub.celsius.temperature() * 100, + 0); // TODO: use differential pressure temperature } bool GCS_MAVLINK_Sub::send_info() diff --git a/libraries/AP_Generator/AP_Generator_RichenPower.cpp b/libraries/AP_Generator/AP_Generator_RichenPower.cpp index fd9a1b248f935..234d0464bff60 100644 --- a/libraries/AP_Generator/AP_Generator_RichenPower.cpp +++ b/libraries/AP_Generator/AP_Generator_RichenPower.cpp @@ -374,7 +374,9 @@ void AP_Generator_RichenPower::send_generator_status(const GCS_MAVLINK &channel) last_reading.output_voltage, // bus_voltage; Voltage of the bus seen at the generator INT16_MAX, // rectifier_temperature std::numeric_limits::quiet_NaN(), // bat_current_setpoint; The target battery current - INT16_MAX // generator temperature + INT16_MAX, // generator temperature + UINT32_MAX, // seconds this generator has run since it was rebooted + INT32_MAX // seconds until this generator requires maintenance ); } diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index abf89571ae3af..e0bcb6d106582 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -236,7 +236,7 @@ class GCS_MAVLINK void send_rc_channels_raw() const; void send_raw_imu(); - void send_scaled_pressure_instance(uint8_t instance, void (*send_fn)(mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature)); + void send_scaled_pressure_instance(uint8_t instance, void (*send_fn)(mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature, int16_t temperature_press_diff)); void send_scaled_pressure(); void send_scaled_pressure2(); virtual void send_scaled_pressure3(); // allow sub to override this diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 6cd06d6170168..7205017b1c21c 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1716,14 +1716,15 @@ void GCS_MAVLINK::send_scaled_imu(uint8_t instance, void (*send_fn)(mavlink_chan // send data for barometer and airspeed sensors instances. In the // case that we run out of instances of one before the other we send // the relevant fields as 0. -void GCS_MAVLINK::send_scaled_pressure_instance(uint8_t instance, void (*send_fn)(mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature)) +void GCS_MAVLINK::send_scaled_pressure_instance(uint8_t instance, void (*send_fn)(mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature, int16_t temperature_press_diff)) { const AP_Baro &barometer = AP::baro(); bool have_data = false; float press_abs = 0.0f; - float temperature = 0.0f; + float temperature = 0.0f; // Absolute pressure temperature + float temperature_press_diff = 0.0f; // TODO: Differential pressure temperature if (instance < barometer.num_instances()) { press_abs = barometer.get_pressure(instance) * 0.01f; temperature = barometer.get_temperature(instance)*100; @@ -1747,7 +1748,8 @@ void GCS_MAVLINK::send_scaled_pressure_instance(uint8_t instance, void (*send_fn AP_HAL::millis(), press_abs, // hectopascal press_diff, // hectopascal - temperature); // 0.01 degrees C + temperature, // 0.01 degrees C + temperature_press_diff); // 0.01 degrees C } void GCS_MAVLINK::send_scaled_pressure() diff --git a/modules/mavlink b/modules/mavlink index 5bb3107fa6b52..fe0d6e4b47c2d 160000 --- a/modules/mavlink +++ b/modules/mavlink @@ -1 +1 @@ -Subproject commit 5bb3107fa6b52651fb5177041e116ae1eb2810ed +Subproject commit fe0d6e4b47c2d3d31680b233c7e9cdd37f4b4eaf