Copter: loiter glitch fix

This commit is contained in:
Leonard Hall 2018-08-21 15:57:45 +09:30 committed by Randy Mackay
parent 31d93f5914
commit 8faa1cce39
1 changed files with 14 additions and 2 deletions

View File

@ -8,8 +8,20 @@
bool Copter::ModeLoiter::init(bool ignore_checks)
{
if (copter.position_ok() || ignore_checks) {
if (!copter.failsafe.radio) {
float target_roll, target_pitch;
// apply SIMPLE mode transform to pilot inputs
update_simple_mode();
// set target to current position
// convert pilot input to lean angles
get_pilot_desired_lean_angles(target_roll, target_pitch, loiter_nav->get_angle_max_cd(), attitude_control->get_althold_lean_angle_max());
// process pilot's roll and pitch input
loiter_nav->set_pilot_desired_acceleration(target_roll, target_pitch, G_Dt);
} else {
// clear out pilot desired acceleration in case radio failsafe event occurs and we do not switch to RTL for some reason
loiter_nav->clear_pilot_desired_acceleration();
}
loiter_nav->init_target();
// initialise position and desired velocity
@ -19,7 +31,7 @@ bool Copter::ModeLoiter::init(bool ignore_checks)
}
return true;
}else{
} else {
return false;
}
}