From deb63c28fc9794b4cba22585679c3a2082bf8c98 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 2 Sep 2023 15:21:34 +1000 Subject: [PATCH] AP_Gripper: allow more libraries to compile with no HAL_GCS_ENABLED --- libraries/AP_Gripper/AP_Gripper_EPM.cpp | 4 ++-- libraries/AP_Gripper/AP_Gripper_Servo.cpp | 8 ++++---- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/AP_Gripper/AP_Gripper_EPM.cpp b/libraries/AP_Gripper/AP_Gripper_EPM.cpp index 5b55219c3a..5762597f50 100644 --- a/libraries/AP_Gripper/AP_Gripper_EPM.cpp +++ b/libraries/AP_Gripper/AP_Gripper_EPM.cpp @@ -65,7 +65,7 @@ void AP_Gripper_EPM::grab() // move the servo output to the grab position SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.grab_pwm); } - gcs().send_text(MAV_SEVERITY_INFO, "Gripper load grabbing"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Gripper load grabbing"); AP::logger().Write_Event(LogEvent::GRIPPER_GRAB); } @@ -89,7 +89,7 @@ void AP_Gripper_EPM::release() // move the servo to the release position SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.release_pwm); } - gcs().send_text(MAV_SEVERITY_INFO, "Gripper load releasing"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Gripper load releasing"); AP::logger().Write_Event(LogEvent::GRIPPER_RELEASE); } diff --git a/libraries/AP_Gripper/AP_Gripper_Servo.cpp b/libraries/AP_Gripper/AP_Gripper_Servo.cpp index 43f08895a8..0ef9957da0 100644 --- a/libraries/AP_Gripper/AP_Gripper_Servo.cpp +++ b/libraries/AP_Gripper/AP_Gripper_Servo.cpp @@ -29,7 +29,7 @@ void AP_Gripper_Servo::grab() // check if we are already grabbed if (config.state == AP_Gripper::STATE_GRABBED) { // inform user that we are already grabbed - gcs().send_text(MAV_SEVERITY_INFO, "Gripper load grabbed"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Gripper load grabbed"); return; } @@ -39,7 +39,7 @@ void AP_Gripper_Servo::grab() // move the servo to the grab position SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.grab_pwm); _last_grab_or_release = AP_HAL::millis(); - gcs().send_text(MAV_SEVERITY_INFO, "Gripper load grabbing"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Gripper load grabbing"); AP::logger().Write_Event(LogEvent::GRIPPER_GRAB); } @@ -54,7 +54,7 @@ void AP_Gripper_Servo::release() // check if we are already released if (config.state == AP_Gripper::STATE_RELEASED) { // inform user that we are already released - gcs().send_text(MAV_SEVERITY_INFO, "Gripper load released"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Gripper load released"); return; } @@ -64,7 +64,7 @@ void AP_Gripper_Servo::release() // move the servo to the release position SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.release_pwm); _last_grab_or_release = AP_HAL::millis(); - gcs().send_text(MAV_SEVERITY_INFO, "Gripper load releasing"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Gripper load releasing"); AP::logger().Write_Event(LogEvent::GRIPPER_RELEASE); }