mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-04 15:08:28 -04:00
69 lines
2.0 KiB
C++
69 lines
2.0 KiB
C++
#include "AP_Mission.h"
|
|
|
|
#include <GCS_MAVLink/GCS.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)
|
|
{
|
|
AP_Gripper *gripper = AP::gripper();
|
|
if (gripper == nullptr) {
|
|
return true;
|
|
}
|
|
|
|
// Note: we ignore the gripper num parameter because we only
|
|
// support one gripper
|
|
switch (cmd.content.gripper.action) {
|
|
case GRIPPER_ACTION_RELEASE:
|
|
gripper->release();
|
|
// Log_Write_Event(DATA_GRIPPER_RELEASE);
|
|
gcs().send_text(MAV_SEVERITY_INFO, "Gripper Released");
|
|
break;
|
|
case GRIPPER_ACTION_GRAB:
|
|
gripper->grab();
|
|
// Log_Write_Event(DATA_GRIPPER_GRAB);
|
|
gcs().send_text(MAV_SEVERITY_INFO, "Gripper Grabbed");
|
|
break;
|
|
default:
|
|
// do nothing
|
|
break;
|
|
}
|
|
|
|
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;
|
|
}
|