mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 01:33:56 -04:00
MotorsMulticopter: move get_hover_throttle_as_pwm to protected
No functional change
This commit is contained in:
parent
c7c6228b5d
commit
e31f2d26c4
@ -120,12 +120,6 @@ AP_MotorsMulticopter::AP_MotorsMulticopter(uint16_t loop_rate, uint16_t speed_hz
|
||||
_batt_voltage_filt.reset(1.0f);
|
||||
};
|
||||
|
||||
// get_hover_throttle_as_pwm - converts hover throttle to pwm (i.e. range 1000 ~ 2000)
|
||||
int16_t AP_MotorsMulticopter::get_hover_throttle_as_pwm() const
|
||||
{
|
||||
return (_throttle_radio_min + (float)(_throttle_radio_max - _throttle_radio_min) * _hover_out / 1000.0f);
|
||||
}
|
||||
|
||||
// output - sends commands to the motors
|
||||
void AP_MotorsMulticopter::output()
|
||||
{
|
||||
@ -313,6 +307,12 @@ void AP_MotorsMulticopter::update_throttle_thr_mix()
|
||||
_throttle_thr_mix = constrain_float(_throttle_thr_mix, 0.1f, 1.0f);
|
||||
}
|
||||
|
||||
// get_hover_throttle_as_pwm - converts hover throttle to pwm (i.e. range 1000 ~ 2000)
|
||||
int16_t AP_MotorsMulticopter::get_hover_throttle_as_pwm() const
|
||||
{
|
||||
return (_throttle_radio_min + (float)(_throttle_radio_max - _throttle_radio_min) * _hover_out / 1000.0f);
|
||||
}
|
||||
|
||||
float AP_MotorsMulticopter::get_compensation_gain() const
|
||||
{
|
||||
// avoid divide by zero
|
||||
|
@ -46,9 +46,6 @@ public:
|
||||
// output - sends commands to the motors
|
||||
virtual void output();
|
||||
|
||||
// get_hover_throttle_as_pwm - converts hover throttle to pwm (i.e. range 1000 ~ 2000)
|
||||
int16_t get_hover_throttle_as_pwm() const;
|
||||
|
||||
// set_yaw_headroom - set yaw headroom (yaw is given at least this amount of pwm)
|
||||
void set_yaw_headroom(int16_t pwm) { _yaw_headroom = pwm; }
|
||||
|
||||
@ -124,6 +121,9 @@ protected:
|
||||
// return gain scheduling gain based on voltage and air density
|
||||
float get_compensation_gain() const;
|
||||
|
||||
// get_hover_throttle_as_pwm - converts hover throttle to pwm (i.e. range 1000 ~ 2000)
|
||||
int16_t get_hover_throttle_as_pwm() const;
|
||||
|
||||
float rel_pwm_to_thr_range(float pwm) const;
|
||||
float thr_range_to_rel_pwm(float thr) const;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user