|
|
|
@ -36,7 +36,7 @@ void Copter::sport_run()
@@ -36,7 +36,7 @@ void Copter::sport_run()
|
|
|
|
|
if (!motors.armed() || ap.throttle_zero || !motors.get_interlock()) { |
|
|
|
|
motors.set_desired_spool_state(AP_Motors::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->get_control_in())-motors.get_throttle_hover()); |
|
|
|
|
pos_control.relax_alt_hold_controllers(0.0f); |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -99,7 +99,7 @@ void Copter::sport_run()
@@ -99,7 +99,7 @@ void Copter::sport_run()
|
|
|
|
|
} |
|
|
|
|
// 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->get_control_in()),false,g.throttle_filt); |
|
|
|
|
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->get_control_in())-motors.get_throttle_hover()); |
|
|
|
|
pos_control.relax_alt_hold_controllers(0.0f); |
|
|
|
|
}else{ |
|
|
|
|
// set motors to full range
|
|
|
|
|
motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); |
|
|
|
|