diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index b28acebb68..7cc8437b20 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -47,8 +47,8 @@ enum ap_message : uint8_t { MSG_SERVO_OUTPUT_RAW, MSG_RADIO_IN, MSG_RAW_IMU1, - MSG_RAW_IMU2, - MSG_RAW_IMU3, + MSG_SCALED_PRESSURE, + MSG_SENSOR_OFFSETS, MSG_GPS_RAW, MSG_GPS_RTK, MSG_GPS2_RAW, diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index fff1090aeb..336516dcbc 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -3234,12 +3234,12 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) send_raw_imu(); break; - case MSG_RAW_IMU2: + case MSG_SCALED_PRESSURE: CHECK_PAYLOAD_SIZE(SCALED_PRESSURE); send_scaled_pressure(); break; - case MSG_RAW_IMU3: + case MSG_SENSOR_OFFSETS: CHECK_PAYLOAD_SIZE(SENSOR_OFFSETS); send_sensor_offsets(); break;