mirror of https://github.com/ArduPilot/ardupilot
Sub: override sending of scaled_pressure3
Without this change we run the risk of sending out the same message with vastly different data in it
This commit is contained in:
parent
695c52be05
commit
c91ba19e7f
|
@ -351,9 +351,9 @@ void NOINLINE Sub::send_rpm(mavlink_channel_t chan)
|
|||
#endif
|
||||
|
||||
// Work around to get temperature sensor data out
|
||||
void NOINLINE Sub::send_temperature(mavlink_channel_t chan)
|
||||
void GCS_MAVLINK_Sub::send_scaled_pressure3()
|
||||
{
|
||||
if (!celsius.healthy()) {
|
||||
if (!sub.celsius.healthy()) {
|
||||
return;
|
||||
}
|
||||
mavlink_msg_scaled_pressure3_send(
|
||||
|
@ -361,7 +361,7 @@ void NOINLINE Sub::send_temperature(mavlink_channel_t chan)
|
|||
AP_HAL::millis(),
|
||||
0,
|
||||
0,
|
||||
celsius.temperature() * 100);
|
||||
sub.celsius.temperature() * 100);
|
||||
}
|
||||
|
||||
bool GCS_MAVLINK_Sub::send_info()
|
||||
|
@ -519,12 +519,6 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
|
|||
sub.send_vfr_hud(chan);
|
||||
break;
|
||||
|
||||
case MSG_RAW_IMU2:
|
||||
CHECK_PAYLOAD_SIZE(SCALED_PRESSURE);
|
||||
send_scaled_pressure();
|
||||
sub.send_temperature(chan);
|
||||
break;
|
||||
|
||||
case MSG_RPM:
|
||||
#if RPM_ENABLED == ENABLED
|
||||
CHECK_PAYLOAD_SIZE(RPM);
|
||||
|
|
|
@ -27,6 +27,9 @@ protected:
|
|||
MAV_RESULT _handle_command_preflight_calibration_baro() override;
|
||||
MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet) override;
|
||||
|
||||
// override sending of scaled_pressure3 to send on-board temperature:
|
||||
void send_scaled_pressure3() override;
|
||||
|
||||
private:
|
||||
|
||||
void handleMessage(mavlink_message_t * msg) override;
|
||||
|
|
|
@ -486,7 +486,6 @@ private:
|
|||
void send_rpm(mavlink_channel_t chan);
|
||||
void rpm_update();
|
||||
#endif
|
||||
void send_temperature(mavlink_channel_t chan);
|
||||
void send_pid_tuning(mavlink_channel_t chan);
|
||||
void gcs_data_stream_send(void);
|
||||
void gcs_check_input(void);
|
||||
|
|
Loading…
Reference in New Issue