Browse Source

only allow positive spoiler and flap controls

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
main
Silvan Fuhrer 3 years ago
parent
commit
089673ff35
  1. 6
      src/modules/control_allocator/ActuatorEffectiveness/ActuatorEffectivenessTiltrotorVTOL.cpp
  2. 4
      src/modules/fw_att_control/FixedwingAttitudeControl.cpp
  3. 2
      src/modules/vtol_att_control/vtol_type.cpp

6
src/modules/control_allocator/ActuatorEffectiveness/ActuatorEffectivenessTiltrotorVTOL.cpp

@ -98,9 +98,9 @@ void ActuatorEffectivenessTiltrotorVTOL::updateSetpoint(const matrix::Vector<flo @@ -98,9 +98,9 @@ void ActuatorEffectivenessTiltrotorVTOL::updateSetpoint(const matrix::Vector<flo
actuator_controls_s actuator_controls_1;
if (_actuator_controls_1_sub.copy(&actuator_controls_1)) {
float control_flaps = -1.f; // For tilt-rotors INDEX_FLAPS is set as combined tilt. TODO: fix this
float airbrakes_control = actuator_controls_1.control[actuator_controls_s::INDEX_AIRBRAKES];
_control_surfaces.applyFlapsAndAirbrakes(control_flaps, airbrakes_control, _first_control_surface_idx, actuator_sp);
const float flaps_control = actuator_controls_1.control[actuator_controls_s::INDEX_FLAPS];
const float airbrakes_control = actuator_controls_1.control[actuator_controls_s::INDEX_AIRBRAKES];
_control_surfaces.applyFlapsAndAirbrakes(flaps_control, airbrakes_control, _first_control_surface_idx, actuator_sp);
}
}

4
src/modules/fw_att_control/FixedwingAttitudeControl.cpp

@ -732,7 +732,7 @@ void FixedwingAttitudeControl::controlFlaps(const float dt) @@ -732,7 +732,7 @@ void FixedwingAttitudeControl::controlFlaps(const float dt)
}
// move the actual control value continuous with time, full flap travel in 1sec
_flaps_setpoint_with_slewrate.update(flap_control, dt);
_flaps_setpoint_with_slewrate.update(math::constrain(flap_control, 0.f, 1.f), dt);
}
void FixedwingAttitudeControl::controlSpoilers(const float dt)
@ -769,7 +769,7 @@ void FixedwingAttitudeControl::controlSpoilers(const float dt) @@ -769,7 +769,7 @@ void FixedwingAttitudeControl::controlSpoilers(const float dt)
}
}
_spoiler_setpoint_with_slewrate.update(spoiler_control, dt);
_spoiler_setpoint_with_slewrate.update(math::constrain(spoiler_control, 0.f, 1.f), dt);
}
void FixedwingAttitudeControl::updateActuatorControlsStatus(float dt)

2
src/modules/vtol_att_control/vtol_type.cpp

@ -168,7 +168,7 @@ void VtolType::update_mc_state() @@ -168,7 +168,7 @@ void VtolType::update_mc_state()
spoiler_setpoint_hover = _params->vt_spoiler_mc_ld;
}
_spoiler_setpoint_with_slewrate.update(spoiler_setpoint_hover, _dt);
_spoiler_setpoint_with_slewrate.update(math::constrain(spoiler_setpoint_hover, 0.f, 1.f), _dt);
_flaps_setpoint_with_slewrate.update(0.f, _dt);
}

Loading…
Cancel
Save