Browse Source

AP_Mission: Reflecting the result of the process

c415-sdk
murata 5 years ago committed by Peter Barker
parent
commit
de9382b0f4
  1. 22
      libraries/AP_Mission/AP_Mission_Commands.cpp

22
libraries/AP_Mission/AP_Mission_Commands.cpp

@ -43,25 +43,21 @@ bool AP_Mission::start_command_do_servorelayevents(const AP_Mission::Mission_Com @@ -43,25 +43,21 @@ bool AP_Mission::start_command_do_servorelayevents(const AP_Mission::Mission_Com
switch (cmd.id) {
case MAV_CMD_DO_SET_SERVO:
sre->do_set_servo(cmd.content.servo.channel, cmd.content.servo.pwm);
return true;
return sre->do_set_servo(cmd.content.servo.channel, cmd.content.servo.pwm);
case MAV_CMD_DO_SET_RELAY:
sre->do_set_relay(cmd.content.relay.num, cmd.content.relay.state);
return true;
return sre->do_set_relay(cmd.content.relay.num, cmd.content.relay.state);
case MAV_CMD_DO_REPEAT_SERVO:
sre->do_repeat_servo(cmd.content.repeat_servo.channel,
cmd.content.repeat_servo.pwm,
cmd.content.repeat_servo.repeat_count,
cmd.content.repeat_servo.cycle_time * 1000.0f);
return true;
return sre->do_repeat_servo(cmd.content.repeat_servo.channel,
cmd.content.repeat_servo.pwm,
cmd.content.repeat_servo.repeat_count,
cmd.content.repeat_servo.cycle_time * 1000.0f);
case MAV_CMD_DO_REPEAT_RELAY:
sre->do_repeat_relay(cmd.content.repeat_relay.num,
cmd.content.repeat_relay.repeat_count,
cmd.content.repeat_relay.cycle_time * 1000.0f);
return true;
return sre->do_repeat_relay(cmd.content.repeat_relay.num,
cmd.content.repeat_relay.repeat_count,
cmd.content.repeat_relay.cycle_time * 1000.0f);
default:
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
AP_HAL::panic("Unhandled servo/relay case");

Loading…
Cancel
Save