diff --git a/AntennaTracker/GCS_Mavlink.cpp b/AntennaTracker/GCS_Mavlink.cpp index a1e4914bbe..f128d79891 100644 --- a/AntennaTracker/GCS_Mavlink.cpp +++ b/AntennaTracker/GCS_Mavlink.cpp @@ -412,7 +412,7 @@ MAV_RESULT GCS_MAVLINK_Tracker::_handle_command_preflight_calibration_baro(const return ret; } -MAV_RESULT GCS_MAVLINK_Tracker::handle_command_component_arm_disarm(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK_Tracker::handle_command_component_arm_disarm(const mavlink_command_int_t &packet) { if (is_equal(packet.param1,1.0f)) { tracker.arm_servos(); diff --git a/AntennaTracker/GCS_Mavlink.h b/AntennaTracker/GCS_Mavlink.h index 5b7796e86a..ecc3953e7b 100644 --- a/AntennaTracker/GCS_Mavlink.h +++ b/AntennaTracker/GCS_Mavlink.h @@ -19,7 +19,7 @@ protected: uint32_t telem_delay() const override { return 0; } - MAV_RESULT handle_command_component_arm_disarm(const mavlink_command_long_t &packet) override; + MAV_RESULT handle_command_component_arm_disarm(const mavlink_command_int_t &packet) override; MAV_RESULT _handle_command_preflight_calibration_baro(const mavlink_message_t &msg) override; MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override;