Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Mavlink: Update to HEAD from master branch and add upstream updates f… #14920

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
3 changes: 2 additions & 1 deletion ArduSub/GCS_Mavlink.cpp
Expand Up @@ -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()
Expand Down
4 changes: 3 additions & 1 deletion libraries/AP_Generator/AP_Generator_RichenPower.cpp
Expand Up @@ -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<double>::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
);
}

Expand Down
2 changes: 1 addition & 1 deletion libraries/GCS_MAVLink/GCS.h
Expand Up @@ -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
Expand Down
8 changes: 5 additions & 3 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Expand Up @@ -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;
Expand All @@ -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()
Expand Down