mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-13 10:03:57 -03:00
Copter: fix heli pos-hold run-up-complete issue
This commit is contained in:
parent
52ca752539
commit
9738e9bc3e
@ -75,6 +75,13 @@ static struct {
|
||||
// poshold_init - initialise PosHold controller
|
||||
bool Copter::poshold_init(bool ignore_checks)
|
||||
{
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// do not allow helis to enter Pos Hold if the Rotor Runup is not complete
|
||||
if (!ignore_checks && !motors.rotor_runup_complete()){
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
|
||||
// fail to initialise PosHold mode if no GPS lock
|
||||
if (!position_ok() && !ignore_checks) {
|
||||
return false;
|
||||
@ -165,7 +172,12 @@ void Copter::poshold_run()
|
||||
takeoff_get_climb_rates(target_climb_rate, takeoff_climb_rate);
|
||||
|
||||
// check for take-off
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// helicopters are held on the ground until rotor speed runup has finished
|
||||
if (ap.land_complete && (takeoff_state.running || (target_climb_rate > 0.0f && motors.rotor_runup_complete()))) {
|
||||
#else
|
||||
if (ap.land_complete && (takeoff_state.running || target_climb_rate > 0.0f)) {
|
||||
#endif
|
||||
if (!takeoff_state.running) {
|
||||
takeoff_timer_start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f));
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user