mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_Motors: remove unused throttle_radio_min, max
Moved to AP_MotorsMulticopter
This commit is contained in:
parent
e84011603c
commit
649a8c461d
@ -31,8 +31,6 @@ AP_Motors::AP_Motors(uint16_t loop_rate, uint16_t speed_hz) :
|
||||
_yaw_control_input(0.0f),
|
||||
_loop_rate(loop_rate),
|
||||
_speed_hz(speed_hz),
|
||||
_throttle_radio_min(1100),
|
||||
_throttle_radio_max(1900),
|
||||
_throttle_in(0.0f),
|
||||
_throttle_filter(),
|
||||
_batt_voltage(0.0f),
|
||||
|
@ -156,8 +156,6 @@ protected:
|
||||
float _yaw_control_input; // desired yaw control from attitude controller, +/- 4500
|
||||
uint16_t _loop_rate; // rate at which output() function is called (normally 400hz)
|
||||
uint16_t _speed_hz; // speed in hz to send updates to motors
|
||||
int16_t _throttle_radio_min; // minimum radio channel pwm
|
||||
int16_t _throttle_radio_max; // maximum radio channel pwm
|
||||
float _throttle_in; // last throttle input from set_throttle caller
|
||||
LowPassFilterFloat _throttle_filter; // throttle input filter
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user