GCS_Mavlink: Adapt to upstream mavlink changes to the SCALED_PRESSURE message

This commit is contained in:
Dr.-Ing. Amilcar do Carmo Lucas 2020-07-27 18:04:00 +02:00 committed by Peter Barker
parent 47bf016a62
commit 7067cbdafd
2 changed files with 6 additions and 4 deletions

View File

@ -236,7 +236,7 @@ public:
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

View File

@ -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()