mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: payload place requires 30% throttle reduction to release
This commit is contained in:
parent
c191a44b27
commit
3551609a21
@ -699,7 +699,7 @@ bool Copter::verify_payload_place()
|
||||
{
|
||||
const uint16_t hover_throttle_calibrate_time = 2000; // milliseconds
|
||||
const uint16_t descend_throttle_calibrate_time = 2000; // milliseconds
|
||||
const float hover_throttle_placed_fraction = 0.8; // i.e. if throttle is less than 80% of hover we have placed
|
||||
const float hover_throttle_placed_fraction = 0.7; // i.e. if throttle is less than 70% of hover we have placed
|
||||
const float descent_throttle_placed_fraction = 0.9; // i.e. if throttle is less than 90% of descent throttle we have placed
|
||||
const uint16_t placed_time = 500; // how long we have to be below a throttle threshold before considering placed
|
||||
|
||||
@ -803,6 +803,7 @@ bool Copter::verify_payload_place()
|
||||
} else {
|
||||
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Gripper not valid");
|
||||
nav_payload_place.state = PayloadPlaceStateType_Ascending_Start;
|
||||
break;
|
||||
}
|
||||
nav_payload_place.state = PayloadPlaceStateType_Releasing;
|
||||
// no break
|
||||
|
Loading…
Reference in New Issue
Block a user