diff --git a/AntennaTracker/GCS_Mavlink.cpp b/AntennaTracker/GCS_Mavlink.cpp index 3b6b2f9473..2243ce5795 100644 --- a/AntennaTracker/GCS_Mavlink.cpp +++ b/AntennaTracker/GCS_Mavlink.cpp @@ -417,6 +417,19 @@ MAV_RESULT GCS_MAVLINK_Tracker::_handle_command_preflight_calibration_baro() return ret; } +MAV_RESULT GCS_MAVLINK_Tracker::handle_command_component_arm_disarm(const mavlink_command_long_t &packet) +{ + if (is_equal(packet.param1,1.0f)) { + tracker.arm_servos(); + return MAV_RESULT_ACCEPTED; + } + if (is_zero(packet.param1)) { + tracker.disarm_servos(); + return MAV_RESULT_ACCEPTED; + } + return MAV_RESULT_UNSUPPORTED; +} + MAV_RESULT GCS_MAVLINK_Tracker::handle_command_long_packet(const mavlink_command_long_t &packet) { // do command @@ -424,17 +437,6 @@ MAV_RESULT GCS_MAVLINK_Tracker::handle_command_long_packet(const mavlink_command switch(packet.command) { - case MAV_CMD_COMPONENT_ARM_DISARM: - if (is_equal(packet.param1,1.0f)) { - tracker.arm_servos(); - return MAV_RESULT_ACCEPTED; - } - if (is_zero(packet.param1)) { - tracker.disarm_servos(); - return MAV_RESULT_ACCEPTED; - } - return MAV_RESULT_UNSUPPORTED; - case MAV_CMD_DO_SET_SERVO: // ensure we are in servo test mode tracker.set_mode(tracker.mode_servotest, ModeReason::SERVOTEST); diff --git a/AntennaTracker/GCS_Mavlink.h b/AntennaTracker/GCS_Mavlink.h index 98578eeb80..6840065ccd 100644 --- a/AntennaTracker/GCS_Mavlink.h +++ b/AntennaTracker/GCS_Mavlink.h @@ -18,6 +18,7 @@ protected: uint8_t sysid_my_gcs() const override; + MAV_RESULT handle_command_component_arm_disarm(const mavlink_command_long_t &packet) override; MAV_RESULT _handle_command_preflight_calibration_baro() override; MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override; diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index 2dbf8f3a97..11dcce6ab4 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -75,6 +75,9 @@ public: Tracker(void); + void arm_servos(); + void disarm_servos(); + private: Parameters g; @@ -211,8 +214,6 @@ private: bool get_home_eeprom(struct Location &loc); bool set_home_eeprom(const Location &temp) WARN_IF_UNUSED; bool set_home(const Location &temp) WARN_IF_UNUSED; - void arm_servos(); - void disarm_servos(); void prepare_servos(); void set_mode(Mode &newmode, ModeReason reason); bool set_mode(uint8_t new_mode, ModeReason reason) override;