mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
GCS_MAVLink: rename MSG_RAW_IMU2 and MSG_RAW_IMU3 to reflect what they send
This commit is contained in:
parent
a40937337d
commit
d5322633ed
@ -47,8 +47,8 @@ enum ap_message : uint8_t {
|
|||||||
MSG_SERVO_OUTPUT_RAW,
|
MSG_SERVO_OUTPUT_RAW,
|
||||||
MSG_RADIO_IN,
|
MSG_RADIO_IN,
|
||||||
MSG_RAW_IMU1,
|
MSG_RAW_IMU1,
|
||||||
MSG_RAW_IMU2,
|
MSG_SCALED_PRESSURE,
|
||||||
MSG_RAW_IMU3,
|
MSG_SENSOR_OFFSETS,
|
||||||
MSG_GPS_RAW,
|
MSG_GPS_RAW,
|
||||||
MSG_GPS_RTK,
|
MSG_GPS_RTK,
|
||||||
MSG_GPS2_RAW,
|
MSG_GPS2_RAW,
|
||||||
|
@ -3234,12 +3234,12 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
|||||||
send_raw_imu();
|
send_raw_imu();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_RAW_IMU2:
|
case MSG_SCALED_PRESSURE:
|
||||||
CHECK_PAYLOAD_SIZE(SCALED_PRESSURE);
|
CHECK_PAYLOAD_SIZE(SCALED_PRESSURE);
|
||||||
send_scaled_pressure();
|
send_scaled_pressure();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_RAW_IMU3:
|
case MSG_SENSOR_OFFSETS:
|
||||||
CHECK_PAYLOAD_SIZE(SENSOR_OFFSETS);
|
CHECK_PAYLOAD_SIZE(SENSOR_OFFSETS);
|
||||||
send_sensor_offsets();
|
send_sensor_offsets();
|
||||||
break;
|
break;
|
||||||
|
Loading…
Reference in New Issue
Block a user