Copter: Tradheli - make new integrator scheme selectable

This commit is contained in:
bnsgeyer 2020-12-01 16:36:36 -05:00 committed by Bill Geyer
parent cd3ee597c7
commit b1bd77f19f
3 changed files with 14 additions and 9 deletions

View File

@ -73,15 +73,20 @@ void Copter::check_dynamic_flight(void)
// should be run between the rate controller and the servo updates. // should be run between the rate controller and the servo updates.
void Copter::update_heli_control_dynamics(void) void Copter::update_heli_control_dynamics(void)
{ {
// Use Leaky_I if we are not moving fast
// attitude_control->use_leaky_i(!heli_flags.dynamic_flight);
attitude_control->use_leaky_i(false);
if (!motors->using_leaky_integrator()) {
//turn off leaky_I
attitude_control->use_leaky_i(false);
if (ap.land_complete || ap.land_complete_maybe) { if (ap.land_complete || ap.land_complete_maybe) {
motors->set_land_complete(true); motors->set_land_complete(true);
} else { } else {
motors->set_land_complete(false); motors->set_land_complete(false);
} }
} else {
// Use Leaky_I if we are not moving fast
attitude_control->use_leaky_i(!heli_flags.dynamic_flight);
motors->set_land_complete(false);
}
if (ap.land_complete || (is_zero(motors->get_desired_rotor_speed()))){ if (ap.land_complete || (is_zero(motors->get_desired_rotor_speed()))){
// if we are landed or there is no rotor power demanded, decrement slew scalar // if we are landed or there is no rotor power demanded, decrement slew scalar

View File

@ -51,13 +51,13 @@ void ModeAcro_Heli::run()
case AP_Motors::SpoolState::GROUND_IDLE: case AP_Motors::SpoolState::GROUND_IDLE:
// If aircraft is landed, set target heading to current and reset the integrator // If aircraft is landed, set target heading to current and reset the integrator
// Otherwise motors could be at ground idle for practice autorotation // Otherwise motors could be at ground idle for practice autorotation
if (copter.ap.land_complete) { 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();
} }
break; break;
case AP_Motors::SpoolState::THROTTLE_UNLIMITED: case AP_Motors::SpoolState::THROTTLE_UNLIMITED:
if (copter.ap.land_complete) { if (copter.ap.land_complete && !motors->using_leaky_integrator()) {
attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_rate_controller_I_terms();
} }
break; break;

View File

@ -56,13 +56,13 @@ void ModeStabilize_Heli::run()
case AP_Motors::SpoolState::GROUND_IDLE: case AP_Motors::SpoolState::GROUND_IDLE:
// If aircraft is landed, set target heading to current and reset the integrator // If aircraft is landed, set target heading to current and reset the integrator
// Otherwise motors could be at ground idle for practice autorotation // Otherwise motors could be at ground idle for practice autorotation
if (copter.ap.land_complete) { 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();
} }
break; break;
case AP_Motors::SpoolState::THROTTLE_UNLIMITED: case AP_Motors::SpoolState::THROTTLE_UNLIMITED:
if (copter.ap.land_complete) { if (copter.ap.land_complete && !motors->using_leaky_integrator()) {
attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_rate_controller_I_terms();
} }
case AP_Motors::SpoolState::SPOOLING_UP: case AP_Motors::SpoolState::SPOOLING_UP: