Browse Source

Copter: payload place skips releasing states if gripper not valid

master
Peter Barker 8 years ago committed by Randy Mackay
parent
commit
c191a44b27
  1. 1
      ArduCopter/commands_logic.cpp

1
ArduCopter/commands_logic.cpp

@ -802,6 +802,7 @@ bool Copter::verify_payload_place() @@ -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

Loading…
Cancel
Save