AntennaTracker: split out a handle_command_component_arm_disarm
This commit is contained in:
parent
0052500d67
commit
c9b906de17
@ -417,14 +417,8 @@ MAV_RESULT GCS_MAVLINK_Tracker::_handle_command_preflight_calibration_baro()
|
|||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
MAV_RESULT GCS_MAVLINK_Tracker::handle_command_long_packet(const mavlink_command_long_t &packet)
|
MAV_RESULT GCS_MAVLINK_Tracker::handle_command_component_arm_disarm(const mavlink_command_long_t &packet)
|
||||||
{
|
{
|
||||||
// do command
|
|
||||||
send_text(MAV_SEVERITY_INFO,"Command received: ");
|
|
||||||
|
|
||||||
switch(packet.command) {
|
|
||||||
|
|
||||||
case MAV_CMD_COMPONENT_ARM_DISARM:
|
|
||||||
if (is_equal(packet.param1,1.0f)) {
|
if (is_equal(packet.param1,1.0f)) {
|
||||||
tracker.arm_servos();
|
tracker.arm_servos();
|
||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
@ -434,6 +428,14 @@ MAV_RESULT GCS_MAVLINK_Tracker::handle_command_long_packet(const mavlink_command
|
|||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
}
|
}
|
||||||
return MAV_RESULT_UNSUPPORTED;
|
return MAV_RESULT_UNSUPPORTED;
|
||||||
|
}
|
||||||
|
|
||||||
|
MAV_RESULT GCS_MAVLINK_Tracker::handle_command_long_packet(const mavlink_command_long_t &packet)
|
||||||
|
{
|
||||||
|
// do command
|
||||||
|
send_text(MAV_SEVERITY_INFO,"Command received: ");
|
||||||
|
|
||||||
|
switch(packet.command) {
|
||||||
|
|
||||||
case MAV_CMD_DO_SET_SERVO:
|
case MAV_CMD_DO_SET_SERVO:
|
||||||
// ensure we are in servo test mode
|
// ensure we are in servo test mode
|
||||||
|
@ -18,6 +18,7 @@ protected:
|
|||||||
|
|
||||||
uint8_t sysid_my_gcs() const override;
|
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_preflight_calibration_baro() override;
|
||||||
MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override;
|
MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override;
|
||||||
|
|
||||||
|
@ -75,6 +75,9 @@ public:
|
|||||||
|
|
||||||
Tracker(void);
|
Tracker(void);
|
||||||
|
|
||||||
|
void arm_servos();
|
||||||
|
void disarm_servos();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
Parameters g;
|
Parameters g;
|
||||||
|
|
||||||
@ -211,8 +214,6 @@ private:
|
|||||||
bool get_home_eeprom(struct Location &loc);
|
bool get_home_eeprom(struct Location &loc);
|
||||||
bool set_home_eeprom(const Location &temp) WARN_IF_UNUSED;
|
bool set_home_eeprom(const Location &temp) WARN_IF_UNUSED;
|
||||||
bool set_home(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 prepare_servos();
|
||||||
void set_mode(Mode &newmode, ModeReason reason);
|
void set_mode(Mode &newmode, ModeReason reason);
|
||||||
bool set_mode(uint8_t new_mode, ModeReason reason) override;
|
bool set_mode(uint8_t new_mode, ModeReason reason) override;
|
||||||
|
Loading…
Reference in New Issue
Block a user