From de9382b0f4b481b4f597a14adfb7f4f59afeb717 Mon Sep 17 00:00:00 2001 From: murata Date: Sat, 13 Jun 2020 06:25:55 +0900 Subject: [PATCH] AP_Mission: Reflecting the result of the process --- libraries/AP_Mission/AP_Mission_Commands.cpp | 22 ++++++++------------ 1 file changed, 9 insertions(+), 13 deletions(-) diff --git a/libraries/AP_Mission/AP_Mission_Commands.cpp b/libraries/AP_Mission/AP_Mission_Commands.cpp index 7835749c38..0c7c73a828 100644 --- a/libraries/AP_Mission/AP_Mission_Commands.cpp +++ b/libraries/AP_Mission/AP_Mission_Commands.cpp @@ -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");