Copter: payload place skips releasing states if gripper not valid

This commit is contained in:
Peter Barker 2016-12-20 14:26:59 +11:00 committed by Randy Mackay
parent 6fd771afc9
commit c191a44b27

View File

@ -802,6 +802,7 @@ bool Copter::verify_payload_place()
g2.gripper.release();
} else {
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Gripper not valid");
nav_payload_place.state = PayloadPlaceStateType_Ascending_Start;
}
nav_payload_place.state = PayloadPlaceStateType_Releasing;
// no break