From 362867415f32d6121bf17bc7e0529591f580d884 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 21 Feb 2024 17:40:35 +1100 Subject: [PATCH] GCS_MAVLink: move gripper up to AP_Vehicle also make the singleton return a reference rather than a pointer --- libraries/GCS_MAVLink/GCS_Common.cpp | 11 ++++------- 1 file changed, 4 insertions(+), 7 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 27b771004a..ac7dd38133 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -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;