diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 0157265c6f..6115fff7db 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -162,7 +162,7 @@ public: void send_heartbeat(uint8_t type, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status); void send_servo_output_raw(bool hil); static void send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour); - void send_accelcal_vehicle_position(uint8_t position); + void send_accelcal_vehicle_position(uint32_t position); // return a bitmap of active channels. Used by libraries to loop // over active channels to send to all active channels diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 21a606d640..2129c44339 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1509,7 +1509,7 @@ void GCS_MAVLINK::send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_C } } -void GCS_MAVLINK::send_accelcal_vehicle_position(uint8_t position) +void GCS_MAVLINK::send_accelcal_vehicle_position(uint32_t position) { if (HAVE_PAYLOAD_SPACE(chan, COMMAND_LONG)) { mavlink_msg_command_long_send(