GCS_MAVLink: move try_send_message of RAW_IMU up to GCS_MAVLINK

This commit is contained in:
Peter Barker 2018-05-03 11:31:47 +10:00 committed by Peter Barker
parent a3a1967e05
commit b51ec1d346
2 changed files with 10 additions and 2 deletions

View File

@ -172,7 +172,7 @@ public:
void send_ahrs2();
void send_system_time();
void send_radio_in();
void send_raw_imu(const AP_InertialSensor &ins, const Compass &compass);
void send_raw_imu();
void send_scaled_pressure();
void send_sensor_offsets(const AP_InertialSensor &ins, const Compass &compass);
void send_ahrs();

View File

@ -1030,8 +1030,11 @@ void GCS_MAVLINK::send_radio_in()
receiver_rssi);
}
void GCS_MAVLINK::send_raw_imu(const AP_InertialSensor &ins, const Compass &compass)
void GCS_MAVLINK::send_raw_imu()
{
const AP_InertialSensor &ins = AP::ins();
const Compass &compass = AP::compass();
const Vector3f &accel = ins.get_accel(0);
const Vector3f &gyro = ins.get_gyro(0);
Vector3f mag;
@ -2765,6 +2768,11 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
send_radio_in();
break;
case MSG_RAW_IMU1:
CHECK_PAYLOAD_SIZE(RAW_IMU);
send_raw_imu();
break;
case MSG_AHRS:
CHECK_PAYLOAD_SIZE(AHRS);
send_ahrs();