AP_MotorsUGV: remove access to enable/disable throttle slewing
This commit is contained in:
parent
23028a659b
commit
6d805b64b6
@ -353,7 +353,7 @@ void AP_MotorsUGV::output_throttle(SRV_Channel::Aux_servo_function_t function, f
|
||||
// slew limit throttle for one iteration
|
||||
void AP_MotorsUGV::slew_limit_throttle(float dt)
|
||||
{
|
||||
if (_use_slew_rate && (_slew_rate > 0)) {
|
||||
if (_slew_rate > 0) {
|
||||
float temp = _slew_rate * dt * 0.01f * (_throttle_max - _throttle_min);
|
||||
if (temp < 1.0f) {
|
||||
temp = 1.0f;
|
||||
|
@ -48,9 +48,6 @@ public:
|
||||
// output to motors and steering servos
|
||||
void output(bool armed, float dt);
|
||||
|
||||
// set when to use slew rate limiter
|
||||
void slew_limit_throttle(bool value) { _use_slew_rate = value; }
|
||||
|
||||
// test steering or throttle output as a percentage of the total (range -100 to +100)
|
||||
// used in response to DO_MOTOR_TEST mavlink command
|
||||
bool output_test_pct(motor_test_order motor_seq, float pct);
|
||||
@ -105,5 +102,4 @@ protected:
|
||||
float _steering; // requested steering as a value from -4500 to +4500
|
||||
float _throttle; // requested throttle as a value from -100 to 100
|
||||
float _last_throttle;
|
||||
bool _use_slew_rate; // true if we should slew limit the throttle for one interation
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user