mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Copter: Loiter stabilizes roll and pitch while landed
This commit is contained in:
parent
9c12b64ba5
commit
1c4db779a1
@ -156,21 +156,16 @@ void Copter::loiter_run()
|
||||
case Loiter_Landed:
|
||||
|
||||
wp_nav.init_loiter_target();
|
||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
||||
// call attitude controller
|
||||
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
||||
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground
|
||||
attitude_control.set_throttle_out(get_throttle_pre_takeoff(channel_throttle->control_in),false,g.throttle_filt);
|
||||
#else
|
||||
// if throttle zero reset attitude and exit immediately
|
||||
if (ap.throttle_zero) {
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
|
||||
}else{
|
||||
} else {
|
||||
motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
}
|
||||
// multicopters do not stabilize roll/pitch/yaw when disarmed
|
||||
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground
|
||||
attitude_control.set_throttle_out(get_throttle_pre_takeoff(channel_throttle->control_in),false,g.throttle_filt);
|
||||
#endif
|
||||
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average);
|
||||
break;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user