Browse Source

FW auto - Add parameter for flaps setting during landing

sbg
bresch 6 years ago committed by Lorenz Meier
parent
commit
20f870137b
  1. 5
      src/modules/fw_att_control/FixedwingAttitudeControl.cpp
  2. 2
      src/modules/fw_att_control/FixedwingAttitudeControl.hpp
  3. 14
      src/modules/fw_att_control/fw_att_control_params.c

5
src/modules/fw_att_control/FixedwingAttitudeControl.cpp

@ -110,6 +110,7 @@ FixedwingAttitudeControl::FixedwingAttitudeControl() : @@ -110,6 +110,7 @@ FixedwingAttitudeControl::FixedwingAttitudeControl() :
_parameter_handles.flaps_scale = param_find("FW_FLAPS_SCL");
_parameter_handles.flaps_takeoff_scale = param_find("FW_FLAPS_TO_SCL");
_parameter_handles.flaps_land_scale = param_find("FW_FLAPS_LND_SCL");
_parameter_handles.flaperon_scale = param_find("FW_FLAPERON_SCL");
_parameter_handles.rattitude_thres = param_find("FW_RATT_TH");
@ -234,6 +235,7 @@ FixedwingAttitudeControl::parameters_update() @@ -234,6 +235,7 @@ FixedwingAttitudeControl::parameters_update()
param_get(_parameter_handles.flaps_scale, &_parameters.flaps_scale);
param_get(_parameter_handles.flaps_takeoff_scale, &_parameters.flaps_takeoff_scale);
param_get(_parameter_handles.flaps_land_scale, &_parameters.flaps_land_scale);
param_get(_parameter_handles.flaperon_scale, &_parameters.flaperon_scale);
param_get(_parameter_handles.rattitude_thres, &_parameters.rattitude_thres);
@ -929,7 +931,8 @@ void FixedwingAttitudeControl::control_flaps(const float dt) @@ -929,7 +931,8 @@ void FixedwingAttitudeControl::control_flaps(const float dt)
case vehicle_attitude_setpoint_s::FLAPS_OFF : flap_control = 0.0f; // no flaps
break;
case vehicle_attitude_setpoint_s::FLAPS_LAND : flap_control = 1.0f * _parameters.flaps_scale; // landing flaps
case vehicle_attitude_setpoint_s::FLAPS_LAND : flap_control = 1.0f * _parameters.flaps_scale *
_parameters.flaps_land_scale; // landing flaps
break;
case vehicle_attitude_setpoint_s::FLAPS_TAKEOFF : flap_control = 1.0f * _parameters.flaps_scale *

2
src/modules/fw_att_control/FixedwingAttitudeControl.hpp

@ -197,6 +197,7 @@ private: @@ -197,6 +197,7 @@ private:
float flaps_scale; /**< Scale factor for flaps */
float flaps_takeoff_scale; /**< Scale factor for flaps on take-off */
float flaps_land_scale; /**< Scale factor for flaps on landing */
float flaperon_scale; /**< Scale factor for flaperons */
float rattitude_thres;
@ -266,6 +267,7 @@ private: @@ -266,6 +267,7 @@ private:
param_t flaps_scale;
param_t flaps_takeoff_scale;
param_t flaps_land_scale;
param_t flaperon_scale;
param_t rattitude_thres;

14
src/modules/fw_att_control/fw_att_control_params.c

@ -499,6 +499,20 @@ PARAM_DEFINE_FLOAT(FW_FLAPS_SCL, 1.0f); @@ -499,6 +499,20 @@ PARAM_DEFINE_FLOAT(FW_FLAPS_SCL, 1.0f);
*/
PARAM_DEFINE_FLOAT(FW_FLAPS_TO_SCL, 0.0f);
/**
* Flaps setting during landing
*
* Sets a fraction of full flaps (FW_FLAPS_SCL) during landing
*
* @unit norm
* @min 0.0
* @max 1.0
* @decimal 2
* @increment 0.01
* @group FW Attitude Control
*/
PARAM_DEFINE_FLOAT(FW_FLAPS_LND_SCL, 1.0f);
/**
* Scale factor for flaperons
*

Loading…
Cancel
Save