diff --git a/libraries/AP_Compass/AP_Compass.h b/libraries/AP_Compass/AP_Compass.h index ccb94a9350..9c47cdb0cb 100644 --- a/libraries/AP_Compass/AP_Compass.h +++ b/libraries/AP_Compass/AP_Compass.h @@ -122,7 +122,7 @@ public: /* handle an incoming MAG_CAL command */ - uint8_t handle_mag_cal_command(const mavlink_command_long_t &packet); + MAV_RESULT handle_mag_cal_command(const mavlink_command_long_t &packet); void send_mag_cal_progress(mavlink_channel_t chan); void send_mag_cal_report(mavlink_channel_t chan); diff --git a/libraries/AP_Compass/AP_Compass_Calibration.cpp b/libraries/AP_Compass/AP_Compass_Calibration.cpp index 5f39bedd2a..10890dc318 100644 --- a/libraries/AP_Compass/AP_Compass_Calibration.cpp +++ b/libraries/AP_Compass/AP_Compass_Calibration.cpp @@ -267,9 +267,9 @@ Compass::_get_cal_mask() const /* handle an incoming MAG_CAL command */ -uint8_t Compass::handle_mag_cal_command(const mavlink_command_long_t &packet) +MAV_RESULT Compass::handle_mag_cal_command(const mavlink_command_long_t &packet) { - uint8_t result = MAV_RESULT_FAILED; + MAV_RESULT result = MAV_RESULT_FAILED; switch (packet.command) { case MAV_CMD_DO_START_MAG_CAL: {