AP_MotorsMulticopter: make thrust to actuator public

This commit is contained in:
Iampete1 2020-11-14 00:16:47 +00:00 committed by Andrew Tridgell
parent dd3ac893b3
commit 681f45c4e0

View File

@ -87,6 +87,9 @@ public:
// parameter check for MOT_PWM_MIN/MAX, returns true if parameters are valid
bool check_mot_pwm_params() const;
// converts desired thrust to linearized actuator output in a range of 0~1
float thrust_to_actuator(float thrust_in);
// set thrust compensation callback
FUNCTOR_TYPEDEF(thrust_compensation_fn_t, void, float *, uint8_t);
void set_thrust_compensation_callback(thrust_compensation_fn_t callback) {
@ -122,9 +125,6 @@ protected:
// convert actuator output (0~1) range to pwm range
int16_t output_to_pwm(float _actuator_output);
// converts desired thrust to linearized actuator output in a range of 0~1
float thrust_to_actuator(float thrust_in);
// adds slew rate limiting to actuator output if MOT_SLEW_TIME > 0 and not shutdown
void set_actuator_with_slew(float& actuator_output, float input);