forked from Archive/PX4-Autopilot
FW controllers: change param FW_ARSP_MODE to FW_USE_AIRSPD
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
This commit is contained in:
parent
1f2a0bc657
commit
9e0c8fd75e
|
@ -34,7 +34,7 @@ param set-default CBRK_IO_SAFETY 22027
|
|||
param set-default EKF2_GPS_POS_X -0.12
|
||||
param set-default EKF2_IMU_POS_X -0.12
|
||||
|
||||
param set-default FW_ARSP_MODE 1
|
||||
param set-default FW_USE_AIRSPD 0
|
||||
param set-default NPFG_PERIOD 25
|
||||
param set-default FW_PR_FF 0.7
|
||||
param set-default FW_PR_I 0.18
|
||||
|
|
|
@ -42,7 +42,21 @@
|
|||
|
||||
bool param_modify_on_import(bson_node_t node)
|
||||
{
|
||||
// 2023-12-06: translate and invert FW_ARSP_MODE-> FW_USE_AIRSPD
|
||||
{
|
||||
if (strcmp("FW_ARSP_MODE", node->name) == 0) {
|
||||
if (node->i32 == 0) {
|
||||
node->i32 = 1;
|
||||
|
||||
} else {
|
||||
node->i32 = 0;
|
||||
}
|
||||
|
||||
strcpy(node->name, "FW_USE_AIRSPD");
|
||||
PX4_INFO("copying and inverting %s -> %s", "FW_ARSP_MODE", "FW_USE_AIRSPD");
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -150,7 +150,7 @@ float FixedwingAttitudeControl::get_airspeed_constrained()
|
|||
// if no airspeed measurement is available out best guess is to use the trim airspeed
|
||||
float airspeed = _param_fw_airspd_trim.get();
|
||||
|
||||
if ((_param_fw_arsp_mode.get() == 0) && airspeed_valid) {
|
||||
if (_param_fw_use_airspd.get() && airspeed_valid) {
|
||||
/* prevent numerical drama by requiring 0.5 m/s minimal speed */
|
||||
airspeed = math::max(0.5f, _airspeed_validated_sub.get().calibrated_airspeed_m_s);
|
||||
|
||||
|
|
|
@ -135,7 +135,7 @@ private:
|
|||
(ParamFloat<px4::params::FW_AIRSPD_MIN>) _param_fw_airspd_min,
|
||||
(ParamFloat<px4::params::FW_AIRSPD_STALL>) _param_fw_airspd_stall,
|
||||
(ParamFloat<px4::params::FW_AIRSPD_TRIM>) _param_fw_airspd_trim,
|
||||
(ParamInt<px4::params::FW_ARSP_MODE>) _param_fw_arsp_mode,
|
||||
(ParamBool<px4::params::FW_USE_AIRSPD>) _param_fw_use_airspd,
|
||||
|
||||
(ParamFloat<px4::params::FW_MAN_P_MAX>) _param_fw_man_p_max,
|
||||
(ParamFloat<px4::params::FW_MAN_R_MAX>) _param_fw_man_r_max,
|
||||
|
|
|
@ -205,7 +205,7 @@ FixedwingPositionControl::airspeed_poll()
|
|||
bool airspeed_valid = _airspeed_valid;
|
||||
airspeed_validated_s airspeed_validated;
|
||||
|
||||
if ((_param_fw_arsp_mode.get() == 0) && _airspeed_validated_sub.update(&airspeed_validated)) {
|
||||
if (_param_fw_use_airspd.get() && _airspeed_validated_sub.update(&airspeed_validated)) {
|
||||
|
||||
_eas2tas = 1.0f; //this is the default value, taken in case of invalid airspeed
|
||||
|
||||
|
|
|
@ -954,7 +954,7 @@ private:
|
|||
(ParamFloat<px4::params::FW_GPSF_R>) _param_nav_gpsf_r,
|
||||
|
||||
// external parameters
|
||||
(ParamInt<px4::params::FW_ARSP_MODE>) _param_fw_arsp_mode,
|
||||
(ParamBool<px4::params::FW_USE_AIRSPD>) _param_fw_use_airspd,
|
||||
|
||||
(ParamFloat<px4::params::FW_PSP_OFF>) _param_fw_psp_off,
|
||||
|
||||
|
|
|
@ -162,7 +162,7 @@ float FixedwingRateControl::get_airspeed_and_update_scaling()
|
|||
// if no airspeed measurement is available out best guess is to use the trim airspeed
|
||||
float airspeed = _param_fw_airspd_trim.get();
|
||||
|
||||
if ((_param_fw_arsp_mode.get() == 0) && airspeed_valid) {
|
||||
if (_param_fw_use_airspd.get() && airspeed_valid) {
|
||||
/* prevent numerical drama by requiring 0.5 m/s minimal speed */
|
||||
airspeed = math::max(0.5f, _airspeed_validated_sub.get().calibrated_airspeed_m_s);
|
||||
|
||||
|
|
|
@ -164,7 +164,7 @@ private:
|
|||
(ParamFloat<px4::params::FW_AIRSPD_MIN>) _param_fw_airspd_min,
|
||||
(ParamFloat<px4::params::FW_AIRSPD_STALL>) _param_fw_airspd_stall,
|
||||
(ParamFloat<px4::params::FW_AIRSPD_TRIM>) _param_fw_airspd_trim,
|
||||
(ParamInt<px4::params::FW_ARSP_MODE>) _param_fw_arsp_mode,
|
||||
(ParamBool<px4::params::FW_USE_AIRSPD>) _param_fw_use_airspd,
|
||||
|
||||
(ParamInt<px4::params::FW_ARSP_SCALE_EN>) _param_fw_arsp_scale_en,
|
||||
|
||||
|
|
|
@ -41,16 +41,18 @@
|
|||
*/
|
||||
|
||||
/**
|
||||
* Airspeed mode
|
||||
* Use airspeed for control
|
||||
*
|
||||
* On vehicles without airspeed sensor this parameter can be used to
|
||||
* enable flying without an airspeed reading
|
||||
* If set to 1, the airspeed measurement data, if valid, is used in the following controllers:
|
||||
* - Rate controller: output scaling
|
||||
* - Attitude controller: coordinated turn controller
|
||||
* - Position controller: airspeed setpoint tracking, takeoff logic
|
||||
* - VTOL: transition logic
|
||||
*
|
||||
* @value 0 Use airspeed in controller
|
||||
* @value 1 Do not use airspeed in controller
|
||||
* @boolean
|
||||
* @group FW Rate Control
|
||||
*/
|
||||
PARAM_DEFINE_INT32(FW_ARSP_MODE, 0);
|
||||
PARAM_DEFINE_INT32(FW_USE_AIRSPD, 1);
|
||||
|
||||
/**
|
||||
* Pitch rate proportional gain.
|
||||
|
|
|
@ -217,7 +217,7 @@ void Standard::update_transition_state()
|
|||
_airspeed_trans_blend_margin;
|
||||
// time based blending when no airspeed sensor is set
|
||||
|
||||
} else if (_param_fw_arsp_mode.get() || !PX4_ISFINITE(_airspeed_validated->calibrated_airspeed_m_s)) {
|
||||
} else if (!_param_fw_use_airspd.get() || !PX4_ISFINITE(_airspeed_validated->calibrated_airspeed_m_s)) {
|
||||
mc_weight = 1.0f - _time_since_trans_start / getMinimumFrontTransitionTime();
|
||||
mc_weight = math::constrain(2.0f * mc_weight, 0.0f, 1.0f);
|
||||
|
||||
|
|
|
@ -324,7 +324,7 @@ void Tailsitter::fill_actuator_outputs()
|
|||
bool Tailsitter::isFrontTransitionCompletedBase()
|
||||
{
|
||||
const bool airspeed_triggers_transition = PX4_ISFINITE(_airspeed_validated->calibrated_airspeed_m_s)
|
||||
&& !_param_fw_arsp_mode.get() ;
|
||||
&& _param_fw_use_airspd.get();
|
||||
|
||||
bool transition_to_fw = false;
|
||||
const float pitch = Eulerf(Quatf(_v_att->q)).theta();
|
||||
|
|
|
@ -243,7 +243,7 @@ void Tiltrotor::update_transition_state()
|
|||
_mc_roll_weight = 1.0f;
|
||||
_mc_yaw_weight = 1.0f;
|
||||
|
||||
if (!_param_fw_arsp_mode.get() && PX4_ISFINITE(_airspeed_validated->calibrated_airspeed_m_s) &&
|
||||
if (_param_fw_use_airspd.get() && PX4_ISFINITE(_airspeed_validated->calibrated_airspeed_m_s) &&
|
||||
_airspeed_validated->calibrated_airspeed_m_s >= getBlendAirspeed()) {
|
||||
const float weight = 1.0f - (_airspeed_validated->calibrated_airspeed_m_s - getBlendAirspeed()) /
|
||||
(getTransitionAirspeed() - getBlendAirspeed());
|
||||
|
@ -252,7 +252,7 @@ void Tiltrotor::update_transition_state()
|
|||
}
|
||||
|
||||
// without airspeed do timed weight changes
|
||||
if ((_param_fw_arsp_mode.get() || !PX4_ISFINITE(_airspeed_validated->calibrated_airspeed_m_s)) &&
|
||||
if ((!_param_fw_use_airspd.get() || !PX4_ISFINITE(_airspeed_validated->calibrated_airspeed_m_s)) &&
|
||||
_time_since_trans_start > getMinimumFrontTransitionTime()) {
|
||||
_mc_roll_weight = 1.0f - (_time_since_trans_start - getMinimumFrontTransitionTime()) /
|
||||
(getOpenLoopFrontTransitionTime() - getMinimumFrontTransitionTime());
|
||||
|
|
|
@ -208,7 +208,7 @@ bool VtolType::isFrontTransitionCompletedBase()
|
|||
{
|
||||
// continue the transition to fw mode while monitoring airspeed for a final switch to fw mode
|
||||
const bool airspeed_triggers_transition = PX4_ISFINITE(_airspeed_validated->calibrated_airspeed_m_s)
|
||||
&& !_param_fw_arsp_mode.get();
|
||||
&& _param_fw_use_airspd.get();
|
||||
const bool minimum_trans_time_elapsed = _time_since_trans_start > getMinimumFrontTransitionTime();
|
||||
const bool openloop_trans_time_elapsed = _time_since_trans_start > getOpenLoopFrontTransitionTime();
|
||||
|
||||
|
|
|
@ -354,7 +354,7 @@ protected:
|
|||
(ParamFloat<px4::params::VT_ARSP_TRANS>) _param_vt_arsp_trans,
|
||||
(ParamFloat<px4::params::VT_F_TRANS_THR>) _param_vt_f_trans_thr,
|
||||
(ParamFloat<px4::params::VT_ARSP_BLEND>) _param_vt_arsp_blend,
|
||||
(ParamBool<px4::params::FW_ARSP_MODE>) _param_fw_arsp_mode,
|
||||
(ParamBool<px4::params::FW_USE_AIRSPD>) _param_fw_use_airspd,
|
||||
(ParamFloat<px4::params::VT_TRANS_TIMEOUT>) _param_vt_trans_timeout,
|
||||
(ParamFloat<px4::params::MPC_XY_CRUISE>) _param_mpc_xy_cruise,
|
||||
(ParamInt<px4::params::VT_FW_DIFTHR_EN>) _param_vt_fw_difthr_en,
|
||||
|
|
Loading…
Reference in New Issue