Copter: fix heli land detector and incoporate reset_I_smoothly

This commit is contained in:
bnsgeyer 2020-12-20 16:40:58 -05:00 committed by Bill Geyer
parent a5bcd65d41
commit 160c992548
15 changed files with 18 additions and 18 deletions

View File

@ -60,8 +60,8 @@ void Copter::update_land_detector()
} else { } else {
#if FRAME_CONFIG == HELI_FRAME #if FRAME_CONFIG == HELI_FRAME
// check that collective pitch is on lower limit (should be constrained by LAND_COL_MIN) // check that collective pitch is below mid collective (zero thrust) position
bool motor_at_lower_limit = motors->limit.throttle_lower; bool motor_at_lower_limit = (motors->get_below_mid_collective() && fabsf(ahrs.get_roll()) < M_PI/2.0f);
#else #else
// check that the average throttle output is near minimum (less than 12.5% hover throttle) // check that the average throttle output is near minimum (less than 12.5% hover throttle)
bool motor_at_lower_limit = motors->limit.throttle_lower && attitude_control->is_throttle_mix_min(); bool motor_at_lower_limit = motors->limit.throttle_lower && attitude_control->is_throttle_mix_min();

View File

@ -485,7 +485,7 @@ void Mode::make_safe_spool_down()
case AP_Motors::SpoolState::SHUT_DOWN: case AP_Motors::SpoolState::SHUT_DOWN:
case AP_Motors::SpoolState::GROUND_IDLE: case AP_Motors::SpoolState::GROUND_IDLE:
// relax controllers during idle states // relax controllers during idle states
attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_rate_controller_I_terms_smoothly();
attitude_control->set_yaw_target_to_current_heading(); attitude_control->set_yaw_target_to_current_heading();
break; break;

View File

@ -34,7 +34,7 @@ void ModeAcro::run()
case AP_Motors::SpoolState::GROUND_IDLE: case AP_Motors::SpoolState::GROUND_IDLE:
// Landed // Landed
attitude_control->set_attitude_target_to_current_attitude(); attitude_control->set_attitude_target_to_current_attitude();
attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_rate_controller_I_terms_smoothly();
break; break;
case AP_Motors::SpoolState::THROTTLE_UNLIMITED: case AP_Motors::SpoolState::THROTTLE_UNLIMITED:

View File

@ -53,12 +53,12 @@ void ModeAcro_Heli::run()
// Otherwise motors could be at ground idle for practice autorotation // Otherwise motors could be at ground idle for practice autorotation
if ((motors->init_targets_on_arming() && motors->using_leaky_integrator()) || (copter.ap.land_complete && !motors->using_leaky_integrator())) { if ((motors->init_targets_on_arming() && motors->using_leaky_integrator()) || (copter.ap.land_complete && !motors->using_leaky_integrator())) {
attitude_control->set_attitude_target_to_current_attitude(); attitude_control->set_attitude_target_to_current_attitude();
attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_rate_controller_I_terms_smoothly();
} }
break; break;
case AP_Motors::SpoolState::THROTTLE_UNLIMITED: case AP_Motors::SpoolState::THROTTLE_UNLIMITED:
if (copter.ap.land_complete && !motors->using_leaky_integrator()) { if (copter.ap.land_complete && !motors->using_leaky_integrator()) {
attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_rate_controller_I_terms_smoothly();
} }
break; break;
case AP_Motors::SpoolState::SPOOLING_UP: case AP_Motors::SpoolState::SPOOLING_UP:

View File

@ -58,7 +58,7 @@ void ModeAltHold::run()
// FALLTHROUGH // FALLTHROUGH
case AltHold_Landed_Pre_Takeoff: case AltHold_Landed_Pre_Takeoff:
attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_rate_controller_I_terms_smoothly();
pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero
break; break;

View File

@ -60,7 +60,7 @@ void AutoTune::run()
} else { } else {
copter.motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); copter.motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
} }
copter.attitude_control->reset_rate_controller_I_terms(); copter.attitude_control->reset_rate_controller_I_terms_smoothly();
copter.attitude_control->set_yaw_target_to_current_heading(); copter.attitude_control->set_yaw_target_to_current_heading();
float target_roll, target_pitch, target_yaw_rate; float target_roll, target_pitch, target_yaw_rate;

View File

@ -98,7 +98,7 @@ void ModeDrift::run()
case AP_Motors::SpoolState::GROUND_IDLE: case AP_Motors::SpoolState::GROUND_IDLE:
// Landed // Landed
attitude_control->set_yaw_target_to_current_heading(); attitude_control->set_yaw_target_to_current_heading();
attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_rate_controller_I_terms_smoothly();
break; break;
case AP_Motors::SpoolState::THROTTLE_UNLIMITED: case AP_Motors::SpoolState::THROTTLE_UNLIMITED:

View File

@ -286,7 +286,7 @@ void ModeFlowHold::run()
// FALLTHROUGH // FALLTHROUGH
case AltHold_Landed_Pre_Takeoff: case AltHold_Landed_Pre_Takeoff:
attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_rate_controller_I_terms_smoothly();
pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero
break; break;

View File

@ -154,7 +154,7 @@ void ModeLoiter::run()
// FALLTHROUGH // FALLTHROUGH
case AltHold_Landed_Pre_Takeoff: case AltHold_Landed_Pre_Takeoff:
attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_rate_controller_I_terms_smoothly();
loiter_nav->init_target(); loiter_nav->init_target();
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(0.0f, 0.0f, 0.0f); attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(0.0f, 0.0f, 0.0f);
pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero

View File

@ -153,7 +153,7 @@ void ModePosHold::run()
// FALLTHROUGH // FALLTHROUGH
case AltHold_Landed_Pre_Takeoff: case AltHold_Landed_Pre_Takeoff:
attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_rate_controller_I_terms_smoothly();
pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero
// set poshold state to pilot override // set poshold state to pilot override

View File

@ -106,7 +106,7 @@ void ModeSport::run()
// FALLTHROUGH // FALLTHROUGH
case AltHold_Landed_Pre_Takeoff: case AltHold_Landed_Pre_Takeoff:
attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_rate_controller_I_terms_smoothly();
pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero
break; break;

View File

@ -38,7 +38,7 @@ void ModeStabilize::run()
case AP_Motors::SpoolState::GROUND_IDLE: case AP_Motors::SpoolState::GROUND_IDLE:
// Landed // Landed
attitude_control->set_yaw_target_to_current_heading(); attitude_control->set_yaw_target_to_current_heading();
attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_rate_controller_I_terms_smoothly();
break; break;
case AP_Motors::SpoolState::THROTTLE_UNLIMITED: case AP_Motors::SpoolState::THROTTLE_UNLIMITED:

View File

@ -58,12 +58,12 @@ void ModeStabilize_Heli::run()
// Otherwise motors could be at ground idle for practice autorotation // Otherwise motors could be at ground idle for practice autorotation
if ((motors->init_targets_on_arming() && motors->using_leaky_integrator()) || (copter.ap.land_complete && !motors->using_leaky_integrator())) { if ((motors->init_targets_on_arming() && motors->using_leaky_integrator()) || (copter.ap.land_complete && !motors->using_leaky_integrator())) {
attitude_control->set_yaw_target_to_current_heading(); attitude_control->set_yaw_target_to_current_heading();
attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_rate_controller_I_terms_smoothly();
} }
break; break;
case AP_Motors::SpoolState::THROTTLE_UNLIMITED: case AP_Motors::SpoolState::THROTTLE_UNLIMITED:
if (copter.ap.land_complete && !motors->using_leaky_integrator()) { if (copter.ap.land_complete && !motors->using_leaky_integrator()) {
attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_rate_controller_I_terms_smoothly();
} }
case AP_Motors::SpoolState::SPOOLING_UP: case AP_Motors::SpoolState::SPOOLING_UP:
case AP_Motors::SpoolState::SPOOLING_DOWN: case AP_Motors::SpoolState::SPOOLING_DOWN:

View File

@ -141,7 +141,7 @@ void ModeSystemId::run()
// init_targets_on_arming is always set true for multicopter. // init_targets_on_arming is always set true for multicopter.
if (motors->init_targets_on_arming()) { if (motors->init_targets_on_arming()) {
attitude_control->set_yaw_target_to_current_heading(); attitude_control->set_yaw_target_to_current_heading();
attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_rate_controller_I_terms_smoothly();
} }
break; break;

View File

@ -253,7 +253,7 @@ void ModeZigZag::manual_control()
FALLTHROUGH; FALLTHROUGH;
case AltHold_Landed_Pre_Takeoff: case AltHold_Landed_Pre_Takeoff:
attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_rate_controller_I_terms_smoothly();
loiter_nav->init_target(); loiter_nav->init_target();
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(0.0f, 0.0f, 0.0f); attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(0.0f, 0.0f, 0.0f);
pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero