diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index b1464b6e76..2fee122927 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -645,14 +645,14 @@ void GCS_MAVLINK_Copter::handle_landing_target(const mavlink_landing_target_t &p #endif } -MAV_RESULT GCS_MAVLINK_Copter::_handle_command_preflight_calibration(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK_Copter::_handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg) { if (is_equal(packet.param6,1.0f)) { // compassmot calibration return copter.mavlink_compassmot(*this); } - return GCS_MAVLINK::_handle_command_preflight_calibration(packet); + return GCS_MAVLINK::_handle_command_preflight_calibration(packet, msg); } diff --git a/ArduCopter/GCS_Mavlink.h b/ArduCopter/GCS_Mavlink.h index 11e1fc4a62..2c0828aae4 100644 --- a/ArduCopter/GCS_Mavlink.h +++ b/ArduCopter/GCS_Mavlink.h @@ -21,7 +21,7 @@ protected: bool params_ready() const override; void send_banner() override; - MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet) override; + MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override; void send_attitude_target() override; void send_position_target_global_int() override;