mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
AP_Mission: move servorelayevents handling into AP_Mission
This commit is contained in:
parent
e79d107761
commit
51d4b2da34
@ -264,6 +264,10 @@ bool AP_Mission::verify_command(const Mission_Command& cmd)
|
|||||||
switch (cmd.id) {
|
switch (cmd.id) {
|
||||||
// do-commands always return true for verify:
|
// do-commands always return true for verify:
|
||||||
case MAV_CMD_DO_GRIPPER:
|
case MAV_CMD_DO_GRIPPER:
|
||||||
|
case MAV_CMD_DO_SET_SERVO:
|
||||||
|
case MAV_CMD_DO_SET_RELAY:
|
||||||
|
case MAV_CMD_DO_REPEAT_SERVO:
|
||||||
|
case MAV_CMD_DO_REPEAT_RELAY:
|
||||||
return true;
|
return true;
|
||||||
default:
|
default:
|
||||||
return _cmd_verify_fn(cmd);
|
return _cmd_verify_fn(cmd);
|
||||||
@ -275,6 +279,11 @@ bool AP_Mission::start_command(const Mission_Command& cmd)
|
|||||||
switch (cmd.id) {
|
switch (cmd.id) {
|
||||||
case MAV_CMD_DO_GRIPPER:
|
case MAV_CMD_DO_GRIPPER:
|
||||||
return start_command_do_gripper(cmd);
|
return start_command_do_gripper(cmd);
|
||||||
|
case MAV_CMD_DO_SET_SERVO:
|
||||||
|
case MAV_CMD_DO_SET_RELAY:
|
||||||
|
case MAV_CMD_DO_REPEAT_SERVO:
|
||||||
|
case MAV_CMD_DO_REPEAT_RELAY:
|
||||||
|
return start_command_do_servorelayevents(cmd);
|
||||||
default:
|
default:
|
||||||
return _cmd_start_fn(cmd);
|
return _cmd_start_fn(cmd);
|
||||||
}
|
}
|
||||||
|
@ -581,6 +581,7 @@ private:
|
|||||||
|
|
||||||
// mission items common to all vehicles:
|
// mission items common to all vehicles:
|
||||||
bool start_command_do_gripper(const AP_Mission::Mission_Command& cmd);
|
bool start_command_do_gripper(const AP_Mission::Mission_Command& cmd);
|
||||||
|
bool start_command_do_servorelayevents(const AP_Mission::Mission_Command& cmd);
|
||||||
};
|
};
|
||||||
|
|
||||||
namespace AP {
|
namespace AP {
|
||||||
|
@ -2,6 +2,7 @@
|
|||||||
|
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#include <AP_Gripper/AP_Gripper.h>
|
#include <AP_Gripper/AP_Gripper.h>
|
||||||
|
#include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
|
||||||
|
|
||||||
bool AP_Mission::start_command_do_gripper(const AP_Mission::Mission_Command& cmd)
|
bool AP_Mission::start_command_do_gripper(const AP_Mission::Mission_Command& cmd)
|
||||||
{
|
{
|
||||||
@ -30,3 +31,38 @@ bool AP_Mission::start_command_do_gripper(const AP_Mission::Mission_Command& cmd
|
|||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool AP_Mission::start_command_do_servorelayevents(const AP_Mission::Mission_Command& cmd)
|
||||||
|
{
|
||||||
|
AP_ServoRelayEvents *sre = AP::servorelayevents();
|
||||||
|
if (sre == nullptr) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
switch (cmd.id) {
|
||||||
|
case MAV_CMD_DO_SET_SERVO:
|
||||||
|
sre->do_set_servo(cmd.content.servo.channel, cmd.content.servo.pwm);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MAV_CMD_DO_SET_RELAY:
|
||||||
|
sre->do_set_relay(cmd.content.relay.num, cmd.content.relay.state);
|
||||||
|
break;
|
||||||
|
|
||||||
|
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);
|
||||||
|
break;
|
||||||
|
|
||||||
|
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);
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user