|
|
|
@ -33,7 +33,8 @@ void Copter::sport_run()
@@ -33,7 +33,8 @@ void Copter::sport_run()
|
|
|
|
|
pos_control.set_accel_z(g.pilot_accel_z); |
|
|
|
|
|
|
|
|
|
// if not armed or throttle at zero, set throttle to zero and exit immediately
|
|
|
|
|
if(!motors.armed() || ap.throttle_zero) { |
|
|
|
|
if (!motors.armed() || ap.throttle_zero || !motors.get_interlock()) { |
|
|
|
|
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_SPIN_WHEN_ARMED); |
|
|
|
|
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); |
|
|
|
|
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average); |
|
|
|
|
return; |
|
|
|
@ -91,10 +92,17 @@ void Copter::sport_run()
@@ -91,10 +92,17 @@ void Copter::sport_run()
|
|
|
|
|
|
|
|
|
|
// reset target lean angles and heading while landed
|
|
|
|
|
if (ap.land_complete) { |
|
|
|
|
if (ap.throttle_zero) { |
|
|
|
|
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_SPIN_WHEN_ARMED); |
|
|
|
|
}else{ |
|
|
|
|
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_THROTTLE_UNLIMITED); |
|
|
|
|
} |
|
|
|
|
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground
|
|
|
|
|
attitude_control.set_throttle_out_unstabilized(get_throttle_pre_takeoff(channel_throttle->control_in),true,g.throttle_filt); |
|
|
|
|
attitude_control.set_throttle_out(get_throttle_pre_takeoff(channel_throttle->control_in),false,g.throttle_filt); |
|
|
|
|
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average); |
|
|
|
|
}else{ |
|
|
|
|
// set motors to full range
|
|
|
|
|
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_THROTTLE_UNLIMITED); |
|
|
|
|
|
|
|
|
|
// call attitude controller
|
|
|
|
|
attitude_control.input_euler_rate_roll_pitch_yaw(target_roll_rate, target_pitch_rate, target_yaw_rate); |
|
|
|
|