diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 74f16ad7ed..427c84f1da 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -1478,7 +1478,7 @@ void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg) } // end handle mavlink -MAV_RESULT GCS_MAVLINK_Copter::handle_flight_termination(const mavlink_command_long_t &packet) { +MAV_RESULT GCS_MAVLINK_Copter::handle_flight_termination(const mavlink_command_int_t &packet) { #if ADVANCED_FAILSAFE == ENABLED if (GCS_MAVLINK::handle_flight_termination(packet) == MAV_RESULT_ACCEPTED) { return MAV_RESULT_ACCEPTED; diff --git a/ArduCopter/GCS_Mavlink.h b/ArduCopter/GCS_Mavlink.h index 59c29caf99..eda1fd42c6 100644 --- a/ArduCopter/GCS_Mavlink.h +++ b/ArduCopter/GCS_Mavlink.h @@ -18,7 +18,7 @@ protected: uint32_t telem_delay() const override; - MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override; + MAV_RESULT handle_flight_termination(const mavlink_command_int_t &packet) override; uint8_t sysid_my_gcs() const override; bool sysid_enforce() const override;