mirror of https://github.com/ArduPilot/ardupilot
Rover: move servorelayevents mission handling into AP_Mission
This commit is contained in:
parent
f97281eb48
commit
0eff11eebe
|
@ -59,24 +59,6 @@ bool Rover::start_command(const AP_Mission::Mission_Command& cmd)
|
||||||
do_set_home(cmd);
|
do_set_home(cmd);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAV_CMD_DO_SET_SERVO:
|
|
||||||
ServoRelayEvents.do_set_servo(cmd.content.servo.channel, cmd.content.servo.pwm);
|
|
||||||
break;
|
|
||||||
|
|
||||||
case MAV_CMD_DO_SET_RELAY:
|
|
||||||
ServoRelayEvents.do_set_relay(cmd.content.relay.num, cmd.content.relay.state);
|
|
||||||
break;
|
|
||||||
|
|
||||||
case MAV_CMD_DO_REPEAT_SERVO:
|
|
||||||
ServoRelayEvents.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);
|
|
||||||
break;
|
|
||||||
|
|
||||||
case MAV_CMD_DO_REPEAT_RELAY:
|
|
||||||
ServoRelayEvents.do_repeat_relay(cmd.content.repeat_relay.num, cmd.content.repeat_relay.repeat_count,
|
|
||||||
cmd.content.repeat_relay.cycle_time * 1000.0f);
|
|
||||||
break;
|
|
||||||
|
|
||||||
#if CAMERA == ENABLED
|
#if CAMERA == ENABLED
|
||||||
case MAV_CMD_DO_CONTROL_VIDEO: // Control on-board camera capturing. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty|
|
case MAV_CMD_DO_CONTROL_VIDEO: // Control on-board camera capturing. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty|
|
||||||
break;
|
break;
|
||||||
|
@ -193,10 +175,6 @@ bool Rover::verify_command(const AP_Mission::Mission_Command& cmd)
|
||||||
// do commands (always return true)
|
// do commands (always return true)
|
||||||
case MAV_CMD_DO_CHANGE_SPEED:
|
case MAV_CMD_DO_CHANGE_SPEED:
|
||||||
case MAV_CMD_DO_SET_HOME:
|
case MAV_CMD_DO_SET_HOME:
|
||||||
case MAV_CMD_DO_SET_SERVO:
|
|
||||||
case MAV_CMD_DO_SET_RELAY:
|
|
||||||
case MAV_CMD_DO_REPEAT_SERVO:
|
|
||||||
case MAV_CMD_DO_REPEAT_RELAY:
|
|
||||||
case MAV_CMD_DO_CONTROL_VIDEO:
|
case MAV_CMD_DO_CONTROL_VIDEO:
|
||||||
case MAV_CMD_DO_DIGICAM_CONFIGURE:
|
case MAV_CMD_DO_DIGICAM_CONFIGURE:
|
||||||
case MAV_CMD_DO_DIGICAM_CONTROL:
|
case MAV_CMD_DO_DIGICAM_CONTROL:
|
||||||
|
|
Loading…
Reference in New Issue