Copter: AltHold stabilizes roll and pitch while landed
This commit is contained in:
parent
3ead74c4be
commit
932cd907d4
@ -138,20 +138,18 @@ void Copter::althold_run()
|
||||
|
||||
case AltHold_Landed:
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
attitude_control.set_yaw_target_to_current_heading();
|
||||
#endif
|
||||
// call attitude controller
|
||||
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
|
||||
attitude_control.set_throttle_out(get_throttle_pre_takeoff(channel_throttle->control_in),false,g.throttle_filt);
|
||||
#else // Multicopter stabilize roll/pitch/yaw when landed
|
||||
attitude_control.set_throttle_out(get_throttle_pre_takeoff(channel_throttle->control_in),false,g.throttle_filt);
|
||||
// if throttle zero reset attitude and exit immediately
|
||||
// set motors to spin-when-armed if throttle at zero, otherwise full range
|
||||
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);
|
||||
}
|
||||
#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