|
|
|
@ -96,7 +96,7 @@ void Copter::loiter_run()
@@ -96,7 +96,7 @@ void Copter::loiter_run()
|
|
|
|
|
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain()); |
|
|
|
|
attitude_control.set_throttle_out(0,false,g.throttle_filt); |
|
|
|
|
#else |
|
|
|
|
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_SPIN_WHEN_ARMED); |
|
|
|
|
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED); |
|
|
|
|
// multicopters do not stabilize roll/pitch/yaw when disarmed
|
|
|
|
|
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); |
|
|
|
|
#endif // HELI_FRAME
|
|
|
|
@ -117,7 +117,7 @@ void Copter::loiter_run()
@@ -117,7 +117,7 @@ void Copter::loiter_run()
|
|
|
|
|
pos_control.set_alt_target_from_climb_rate(-abs(g.land_speed), G_Dt, false); |
|
|
|
|
pos_control.update_z_controller(); |
|
|
|
|
#else |
|
|
|
|
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_SHUT_DOWN); |
|
|
|
|
motors.set_desired_spool_state(AP_Motors::DESIRED_SHUT_DOWN); |
|
|
|
|
wp_nav.init_loiter_target(); |
|
|
|
|
// multicopters do not stabilize roll/pitch/yaw when motors are stopped
|
|
|
|
|
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); |
|
|
|
@ -139,7 +139,7 @@ void Copter::loiter_run()
@@ -139,7 +139,7 @@ void Copter::loiter_run()
|
|
|
|
|
takeoff_get_climb_rates(target_climb_rate, takeoff_climb_rate); |
|
|
|
|
|
|
|
|
|
// set motors to full range
|
|
|
|
|
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_THROTTLE_UNLIMITED); |
|
|
|
|
motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); |
|
|
|
|
|
|
|
|
|
// run loiter controller
|
|
|
|
|
wp_nav.update_loiter(ekfGndSpdLimit, ekfNavVelGainScaler); |
|
|
|
@ -163,9 +163,9 @@ void Copter::loiter_run()
@@ -163,9 +163,9 @@ void Copter::loiter_run()
|
|
|
|
|
#else |
|
|
|
|
// if throttle zero reset attitude and exit immediately
|
|
|
|
|
if (ap.throttle_zero) { |
|
|
|
|
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_SPIN_WHEN_ARMED); |
|
|
|
|
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED); |
|
|
|
|
}else{ |
|
|
|
|
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_THROTTLE_UNLIMITED); |
|
|
|
|
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
|
|
|
|
@ -177,7 +177,7 @@ void Copter::loiter_run()
@@ -177,7 +177,7 @@ void Copter::loiter_run()
|
|
|
|
|
case Loiter_Flying: |
|
|
|
|
|
|
|
|
|
// set motors to full range
|
|
|
|
|
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_THROTTLE_UNLIMITED); |
|
|
|
|
motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); |
|
|
|
|
|
|
|
|
|
// run loiter controller
|
|
|
|
|
wp_nav.update_loiter(ekfGndSpdLimit, ekfNavVelGainScaler); |
|
|
|
|