AP_Gripper: log event when gripper grabbed or released

This commit is contained in:
Peter Barker 2019-10-25 17:13:14 +11:00 committed by Randy Mackay
parent b8cbd64c86
commit 08d99b96ec
2 changed files with 7 additions and 0 deletions

View File

@ -11,6 +11,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_Logger/AP_Logger.h>
#ifdef UAVCAN_NODE_FILE
#include <fcntl.h>
#include <stdio.h>
@ -60,6 +61,7 @@ void AP_Gripper_EPM::grab()
SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.grab_pwm);
}
gcs().send_text(MAV_SEVERITY_INFO, "Gripper load grabbing");
AP::logger().Write_Event(LogEvent::GRIPPER_GRAB);
}
// release - move epm pwm output to the release position
@ -83,6 +85,7 @@ void AP_Gripper_EPM::release()
SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.release_pwm);
}
gcs().send_text(MAV_SEVERITY_INFO, "Gripper load releasing");
AP::logger().Write_Event(LogEvent::GRIPPER_RELEASE);
}
// neutral - return the epm pwm output to the neutral position

View File

@ -1,5 +1,7 @@
#include <AP_Gripper/AP_Gripper_Servo.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_Logger/AP_Logger.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <SITL/SITL.h>
#endif
@ -22,6 +24,7 @@ void AP_Gripper_Servo::grab()
is_released = true;
#endif
gcs().send_text(MAV_SEVERITY_INFO, "Gripper load grabbing");
AP::logger().Write_Event(LogEvent::GRIPPER_GRAB);
}
void AP_Gripper_Servo::release()
@ -34,6 +37,7 @@ void AP_Gripper_Servo::release()
is_released = false;
#endif
gcs().send_text(MAV_SEVERITY_INFO, "Gripper load releasing");
AP::logger().Write_Event(LogEvent::GRIPPER_RELEASE);
}
bool AP_Gripper_Servo::has_state_pwm(const uint16_t pwm) const