mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: add comments to set_land_complete
This commit is contained in:
parent
747344a8ba
commit
0732ad3957
@ -79,6 +79,7 @@ void Copter::update_land_detector()
|
|||||||
set_land_complete_maybe(ap.land_complete || (land_detector_count >= LAND_DETECTOR_MAYBE_TRIGGER_SEC*MAIN_LOOP_RATE));
|
set_land_complete_maybe(ap.land_complete || (land_detector_count >= LAND_DETECTOR_MAYBE_TRIGGER_SEC*MAIN_LOOP_RATE));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// set land_complete flag and disarm motors if disarm-on-land is configured
|
||||||
void Copter::set_land_complete(bool b)
|
void Copter::set_land_complete(bool b)
|
||||||
{
|
{
|
||||||
// if no change, exit immediately
|
// if no change, exit immediately
|
||||||
@ -94,6 +95,7 @@ void Copter::set_land_complete(bool b)
|
|||||||
}
|
}
|
||||||
ap.land_complete = b;
|
ap.land_complete = b;
|
||||||
|
|
||||||
|
// trigger disarm-on-land if configured
|
||||||
bool disarm_on_land_configured = (g.throttle_behavior & THR_BEHAVE_DISARM_ON_LAND_DETECT) != 0;
|
bool disarm_on_land_configured = (g.throttle_behavior & THR_BEHAVE_DISARM_ON_LAND_DETECT) != 0;
|
||||||
bool mode_disarms_on_land = mode_allows_arming(control_mode,false) && !mode_has_manual_throttle(control_mode);
|
bool mode_disarms_on_land = mode_allows_arming(control_mode,false) && !mode_has_manual_throttle(control_mode);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user