Browse Source

Copter: autotune uses AP_Motors set_desired_spool_state

master
Randy Mackay 9 years ago
parent
commit
478b9af0f3
  1. 8
      ArduCopter/control_autotune.cpp

8
ArduCopter/control_autotune.cpp

@ -269,7 +269,7 @@ void Copter::autotune_run()
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately // if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
// this should not actually be possible because of the autotune_init() checks // this should not actually be possible because of the autotune_init() checks
if (!motors.armed() || !ap.auto_armed || !motors.get_interlock()) { if (!motors.armed() || !ap.auto_armed || !motors.get_interlock()) {
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_SPIN_WHEN_ARMED); motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); 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); pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average);
return; return;
@ -298,9 +298,9 @@ void Copter::autotune_run()
// reset target lean angles and heading while landed // reset target lean angles and heading while landed
if (ap.land_complete) { if (ap.land_complete) {
if (ap.throttle_zero) { 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{ }else{
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_THROTTLE_UNLIMITED); motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
} }
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground // 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); attitude_control.set_throttle_out(get_throttle_pre_takeoff(channel_throttle->control_in),false,g.throttle_filt);
@ -328,7 +328,7 @@ void Copter::autotune_run()
} }
// set motors to full range // 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);
// if pilot override call attitude controller // if pilot override call attitude controller
if (autotune_state.pilot_override || autotune_state.mode != AUTOTUNE_MODE_TUNING) { if (autotune_state.pilot_override || autotune_state.mode != AUTOTUNE_MODE_TUNING) {

Loading…
Cancel
Save