mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
GCS_MAVLink: move gripper up to AP_Vehicle
also make the singleton return a reference rather than a pointer
This commit is contained in:
parent
9bdb886bb8
commit
362867415f
@ -4705,14 +4705,11 @@ MAV_RESULT GCS_MAVLINK::handle_command_set_ekf_source_set(const mavlink_command_
|
||||
#if AP_GRIPPER_ENABLED
|
||||
MAV_RESULT GCS_MAVLINK::handle_command_do_gripper(const mavlink_command_int_t &packet)
|
||||
{
|
||||
AP_Gripper *gripper = AP::gripper();
|
||||
if (gripper == nullptr) {
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
AP_Gripper &gripper = AP::gripper();
|
||||
|
||||
// param1 : gripper number (ignored)
|
||||
// param2 : action (0=release, 1=grab). See GRIPPER_ACTIONS enum.
|
||||
if(!gripper->enabled()) {
|
||||
if(!gripper.enabled()) {
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
|
||||
@ -4720,10 +4717,10 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_gripper(const mavlink_command_int_t &p
|
||||
|
||||
switch ((uint8_t)packet.param2) {
|
||||
case GRIPPER_ACTION_RELEASE:
|
||||
gripper->release();
|
||||
gripper.release();
|
||||
break;
|
||||
case GRIPPER_ACTION_GRAB:
|
||||
gripper->grab();
|
||||
gripper.grab();
|
||||
break;
|
||||
default:
|
||||
result = MAV_RESULT_FAILED;
|
||||
|
Loading…
Reference in New Issue
Block a user