AP_Gripper: allow compilation with HAL_LOGGING_ENABLED false

This commit is contained in:
Peter Barker 2023-07-14 10:58:06 +10:00 committed by Andrew Tridgell
parent fa8f3b5715
commit 1c395966ce
2 changed files with 4 additions and 4 deletions

View File

@ -66,7 +66,7 @@ void AP_Gripper_EPM::grab()
SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.grab_pwm); 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); LOGGER_WRITE_EVENT(LogEvent::GRIPPER_GRAB);
} }
// release - move epm pwm output to the release position // release - move epm pwm output to the release position
@ -90,7 +90,7 @@ void AP_Gripper_EPM::release()
SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.release_pwm); 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); LOGGER_WRITE_EVENT(LogEvent::GRIPPER_RELEASE);
} }
// neutral - return the epm pwm output to the neutral position // neutral - return the epm pwm output to the neutral position

View File

@ -40,7 +40,7 @@ void AP_Gripper_Servo::grab()
SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.grab_pwm); SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.grab_pwm);
_last_grab_or_release = AP_HAL::millis(); _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); LOGGER_WRITE_EVENT(LogEvent::GRIPPER_GRAB);
} }
void AP_Gripper_Servo::release() void AP_Gripper_Servo::release()
@ -65,7 +65,7 @@ void AP_Gripper_Servo::release()
SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.release_pwm); SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.release_pwm);
_last_grab_or_release = AP_HAL::millis(); _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); LOGGER_WRITE_EVENT(LogEvent::GRIPPER_RELEASE);
} }
bool AP_Gripper_Servo::has_state_pwm(const uint16_t pwm) const bool AP_Gripper_Servo::has_state_pwm(const uint16_t pwm) const