mirror of https://github.com/ArduPilot/ardupilot
AP_Mission: move gripper up to AP_Vehicle
also make the singleton return a reference rather than a pointer
This commit is contained in:
parent
9a1a412152
commit
b41d82c989
|
@ -38,21 +38,18 @@ bool AP_Mission::start_command_do_aux_function(const AP_Mission::Mission_Command
|
|||
#if AP_GRIPPER_ENABLED
|
||||
bool AP_Mission::start_command_do_gripper(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
AP_Gripper *gripper = AP::gripper();
|
||||
if (gripper == nullptr) {
|
||||
return false;
|
||||
}
|
||||
AP_Gripper &gripper = AP::gripper();
|
||||
|
||||
// Note: we ignore the gripper num parameter because we only
|
||||
// support one gripper
|
||||
switch (cmd.content.gripper.action) {
|
||||
case GRIPPER_ACTION_RELEASE:
|
||||
gripper->release();
|
||||
gripper.release();
|
||||
// Log_Write_Event(DATA_GRIPPER_RELEASE);
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Gripper Released");
|
||||
return true;
|
||||
case GRIPPER_ACTION_GRAB:
|
||||
gripper->grab();
|
||||
gripper.grab();
|
||||
// Log_Write_Event(DATA_GRIPPER_GRAB);
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Gripper Grabbed");
|
||||
return true;
|
||||
|
|
Loading…
Reference in New Issue