diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index 8bbaba74cf..2da1cb7535 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -799,7 +799,7 @@ uint64_t GCS_MAVLINK_Sub::capabilities() const ); } -MAV_RESULT GCS_MAVLINK_Sub::handle_flight_termination(const mavlink_command_long_t &packet) { +MAV_RESULT GCS_MAVLINK_Sub::handle_flight_termination(const mavlink_command_int_t &packet) { if (packet.param1 > 0.5f) { sub.arming.disarm(AP_Arming::Method::TERMINATION); return MAV_RESULT_ACCEPTED; diff --git a/ArduSub/GCS_Mavlink.h b/ArduSub/GCS_Mavlink.h index 17a3e77a8d..c185fa1b18 100644 --- a/ArduSub/GCS_Mavlink.h +++ b/ArduSub/GCS_Mavlink.h @@ -15,7 +15,7 @@ protected: return 0; }; - MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override; + MAV_RESULT handle_flight_termination(const mavlink_command_int_t &packet) override; MAV_RESULT handle_command_do_set_roi(const Location &roi_loc) override; MAV_RESULT _handle_command_preflight_calibration_baro(const mavlink_message_t &msg) override;