AP_Gripper: allow more libraries to compile with no HAL_GCS_ENABLED

This commit is contained in:
Peter Barker 2023-09-02 15:21:34 +10:00 committed by Peter Barker
parent eb6f3f5135
commit deb63c28fc
2 changed files with 6 additions and 6 deletions

View File

@ -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);
}

View File

@ -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);
}