Copter: desired-ground-idle replaces spin-when-armed

This commit is contained in:
Leonard Hall 2018-12-28 20:12:28 +09:00 committed by Randy Mackay
parent 4edc464b83
commit 2ddb3f6697
9 changed files with 10 additions and 10 deletions

View File

@ -383,7 +383,7 @@ void Copter::Mode::zero_throttle_and_relax_ac()
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(0.0f, 0.0f, 0.0f);
attitude_control->set_throttle_out(0.0f, false, copter.g.throttle_filt);
#else
motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
// multicopters do not stabilize roll/pitch/yaw when disarmed
attitude_control->set_throttle_out_unstabilized(0.0f, true, copter.g.throttle_filt);
#endif

View File

@ -111,7 +111,7 @@ void Copter::ModeAltHold::run()
case AltHold_Landed:
// set motors to spin-when-armed if throttle below deadzone, otherwise full range (but motors will only spin at min throttle)
if (target_climb_rate < 0.0f) {
motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
} else {
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
}

View File

@ -54,7 +54,7 @@ void Copter::AutoTune::run()
// set motors to spin-when-armed if throttle below deadzone, otherwise full range (but motors will only spin at min throttle)
if (target_climb_rate < 0.0f) {
copter.motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
copter.motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
} else {
copter.motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
}

View File

@ -336,7 +336,7 @@ void Copter::ModeFlowHold::run()
case FlowHold_Landed:
// set motors to spin-when-armed if throttle below deadzone, otherwise full range (but motors will only spin at min throttle)
if (target_climb_rate < 0.0f) {
copter.motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
copter.motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
} else {
copter.motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
}

View File

@ -113,7 +113,7 @@ void Copter::ModeLand::nogps_run()
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
attitude_control->set_throttle_out(0,false,g.throttle_filt);
#else
motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
// multicopters do not stabilize roll/pitch/yaw when disarmed
attitude_control->set_throttle_out_unstabilized(0,true,g.throttle_filt);
#endif

View File

@ -182,7 +182,7 @@ void Copter::ModeLoiter::run()
case Loiter_Landed:
// set motors to spin-when-armed if throttle below deadzone, otherwise full range (but motors will only spin at min throttle)
if (target_climb_rate < 0.0f) {
motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
} else {
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
}

View File

@ -186,7 +186,7 @@ void Copter::ModePosHold::run()
if (ap.land_complete) {
// set motors to spin-when-armed if throttle below deadzone, otherwise full range (but motors will only spin at min throttle)
if (target_climb_rate < 0.0f) {
motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
} else {
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
}

View File

@ -132,7 +132,7 @@ void Copter::ModeSport::run()
case Sport_Landed:
// set motors to spin-when-armed if throttle below deadzone, otherwise full range (but motors will only spin at min throttle)
if (target_climb_rate < 0.0f) {
motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
} else {
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
}

View File

@ -110,7 +110,7 @@ void Copter::ModeThrow::run()
// prevent motors from rotating before the throw is detected unless enabled by the user
if (g.throw_motor_start == 1) {
motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
} else {
motors->set_desired_spool_state(AP_Motors::DESIRED_SHUT_DOWN);
}
@ -123,7 +123,7 @@ void Copter::ModeThrow::run()
// prevent motors from rotating before the throw is detected unless enabled by the user
if (g.throw_motor_start == 1) {
motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
motors->set_desired_spool_state(AP_Motors::DESIRED_GROUND_IDLE);
} else {
motors->set_desired_spool_state(AP_Motors::DESIRED_SHUT_DOWN);
}