mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
GCS_MAVLink: move try_send_message sending of sensor offsets up
This commit is contained in:
parent
5736aa6ef3
commit
8cb2b5809f
@ -174,7 +174,7 @@ public:
|
||||
void send_radio_in();
|
||||
void send_raw_imu();
|
||||
void send_scaled_pressure();
|
||||
void send_sensor_offsets(const AP_InertialSensor &ins, const Compass &compass);
|
||||
void send_sensor_offsets();
|
||||
void send_ahrs();
|
||||
void send_battery2();
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
|
@ -1156,8 +1156,11 @@ void GCS_MAVLINK::send_scaled_pressure()
|
||||
}
|
||||
}
|
||||
|
||||
void GCS_MAVLINK::send_sensor_offsets(const AP_InertialSensor &ins, const Compass &compass)
|
||||
void GCS_MAVLINK::send_sensor_offsets()
|
||||
{
|
||||
const AP_InertialSensor &ins = AP::ins();
|
||||
const Compass &compass = AP::compass();
|
||||
|
||||
// run this message at a much lower rate - otherwise it
|
||||
// pointlessly wastes quite a lot of bandwidth
|
||||
static uint8_t counter;
|
||||
@ -2773,6 +2776,11 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
||||
send_raw_imu();
|
||||
break;
|
||||
|
||||
case MSG_RAW_IMU3:
|
||||
CHECK_PAYLOAD_SIZE(SENSOR_OFFSETS);
|
||||
send_sensor_offsets();
|
||||
break;
|
||||
|
||||
case MSG_AHRS:
|
||||
CHECK_PAYLOAD_SIZE(AHRS);
|
||||
send_ahrs();
|
||||
|
Loading…
Reference in New Issue
Block a user