AntennaTracker: now supports mavlink arm and disarm commands to disable antenna servo outputs

This commit is contained in:
Mike McCauley 2014-03-04 10:37:15 +10:00 committed by Andrew Tridgell
parent c90d3ff59e
commit b1e00c695e
2 changed files with 29 additions and 3 deletions

View File

@ -866,6 +866,22 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break; break;
} }
case MAV_CMD_COMPONENT_ARM_DISARM:
if (packet.target_component == MAV_COMP_ID_SYSTEM_CONTROL) {
if (packet.param1 == 1.0f) {
arm_servos();
result = MAV_RESULT_ACCEPTED;
} else if (packet.param1 == 0.0f) {
disarm_servos();
result = MAV_RESULT_ACCEPTED;
} else {
result = MAV_RESULT_UNSUPPORTED;
}
} else {
result = MAV_RESULT_UNSUPPORTED;
}
break;
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN: case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
{ {
if (packet.param1 == 1 || packet.param1 == 3) { if (packet.param1 == 1 || packet.param1 == 3) {

View File

@ -72,10 +72,8 @@ static void init_tracker()
channel_yaw.calc_pwm(); channel_yaw.calc_pwm();
channel_pitch.calc_pwm(); channel_pitch.calc_pwm();
channel_yaw.enable_out();
channel_pitch.enable_out();
home_loc = get_home_eeprom(); // GPS may update this later home_loc = get_home_eeprom(); // GPS may update this later
arm_servos();
gcs_send_text_P(SEVERITY_LOW,PSTR("\nReady to track.")); gcs_send_text_P(SEVERITY_LOW,PSTR("\nReady to track."));
hal.scheduler->delay(1000); // Why???? hal.scheduler->delay(1000); // Why????
@ -191,3 +189,15 @@ static void set_home(struct Location temp)
set_home_eeprom(temp); set_home_eeprom(temp);
home_loc = temp; home_loc = temp;
} }
static void arm_servos()
{
channel_yaw.enable_out();
channel_pitch.enable_out();
}
static void disarm_servos()
{
channel_yaw.disable_out();
channel_pitch.disable_out();
}