mirror of https://github.com/ArduPilot/ardupilot
AP_Gripper: correct emitting of grabbed/released messages
these strigs would only be released if release() or grab were called a second time
This commit is contained in:
parent
3630e772b1
commit
56a7e520b6
|
@ -104,8 +104,10 @@ void AP_Gripper_Servo::update_gripper()
|
|||
// Check for successful grabbed or released
|
||||
if (config.state == AP_Gripper::STATE_GRABBING && has_state_pwm(config.grab_pwm)) {
|
||||
config.state = AP_Gripper::STATE_GRABBED;
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Gripper load grabbed");
|
||||
} else if (config.state == AP_Gripper::STATE_RELEASING && has_state_pwm(config.release_pwm)) {
|
||||
config.state = AP_Gripper::STATE_RELEASED;
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Gripper load released");
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue