Clarify Documentation of THR_MDL_FAC

The documentation of the thrust model parameter `THR_MDL_FAC` did not
mention both thrust and "PWM" being relative values. Also the use of the
term PWM could be misleading, since the model is applicable to CAN ESCs
as well.

This commit rephrases the user documentation string and a few source
code comments, but no logic changes are made.

Closes PX4/Firmware#13105
This commit is contained in:
Lasse 2019-10-08 19:33:42 +02:00 committed by Beat Küng
parent c1faea8d32
commit 5ac0a3043b
4 changed files with 12 additions and 8 deletions

View File

@ -241,7 +241,7 @@ public:
virtual unsigned get_trim(float *trim) = 0;
/*
* @brief Sets the thrust factor used to calculate mapping from desired thrust to pwm.
* @brief Sets the thrust factor used to calculate mapping from desired thrust to motor control signal output.
*
* @param[in] val The value
*/
@ -444,7 +444,7 @@ public:
}
/**
* @brief Sets the thrust factor used to calculate mapping from desired thrust to pwm.
* @brief Sets the thrust factor used to calculate mapping from desired thrust to motor control signal output.
*
* @param[in] val The value
*/
@ -708,7 +708,7 @@ public:
}
/**
* @brief Sets the thrust factor used to calculate mapping from desired thrust to pwm.
* @brief Sets the thrust factor used to calculate mapping from desired thrust to motor control signal output.
*
* @param[in] val The value
*/

View File

@ -233,7 +233,7 @@ private:
DEFINE_PARAMETERS(
(ParamInt<px4::params::MC_AIRMODE>) _param_mc_airmode, ///< multicopter air-mode
(ParamFloat<px4::params::MOT_SLEW_MAX>) _param_mot_slew_max,
(ParamFloat<px4::params::THR_MDL_FAC>) _param_thr_mdl_fac, ///< thrust to pwm modelling factor
(ParamFloat<px4::params::THR_MDL_FAC>) _param_thr_mdl_fac, ///< thrust to motor control signal modelling factor
(ParamInt<px4::params::MOT_ORDERING>) _param_mot_ordering,
(ParamInt<px4::params::CBRK_IO_SAFETY>) _param_cbrk_io_safety

View File

@ -235,7 +235,7 @@ enum { /* DSM bind states */
#define PX4IO_P_SETUP_MOTOR_SLEW_MAX 24 /**< max motor slew rate */
#define PX4IO_P_SETUP_THR_MDL_FAC 25 /**< factor for modelling static pwm output to thrust relationship */
#define PX4IO_P_SETUP_THR_MDL_FAC 25 /**< factor for modelling motor control signal output to static thrust relationship */
#define PX4IO_P_SETUP_THERMAL 26 /**< thermal management */

View File

@ -55,10 +55,14 @@
PARAM_DEFINE_FLOAT(MOT_SLEW_MAX, 0.0f);
/**
* Thrust to PWM model parameter
* Thrust to motor control signal model parameter
*
* Parameter used to model the relationship between static thrust and motor
* input PWM. Model is: thrust = (1-factor)*PWM + factor * PWM^2
* Parameter used to model the nonlinear relationship between
* motor control signal (e.g. PWM) and static thrust.
*
* The model is: rel_thrust = factor * rel_signal^2 + (1-factor) * rel_signal,
* where rel_thrust is the normalized thrust between 0 and 1, and
* rel_signal is the relative motor control signal between 0 and 1.
*
* @min 0.0
* @max 1.0