From 785da8add95577ad7541533c32c5325ff1e90530 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 7 Aug 2018 16:14:43 +0900 Subject: [PATCH] AP_WheelRateControl: lib to control wheel rate with encoders --- .../AP_WheelEncoder/AP_WheelRateControl.cpp | 188 ++++++++++++++++++ .../AP_WheelEncoder/AP_WheelRateControl.h | 73 +++++++ 2 files changed, 261 insertions(+) create mode 100644 libraries/AP_WheelEncoder/AP_WheelRateControl.cpp create mode 100644 libraries/AP_WheelEncoder/AP_WheelRateControl.h diff --git a/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp b/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp new file mode 100644 index 0000000000..e283cbfae0 --- /dev/null +++ b/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp @@ -0,0 +1,188 @@ +#include + +extern const AP_HAL::HAL& hal; + +const AP_Param::GroupInfo AP_WheelRateControl::var_info[] = { + // @Param: _ENABLE + // @DisplayName: Wheel rate control enable/disable + // @Description: Enable or disable wheel rate control + // @Values: 0:Disabled,1:Enabled + // @User: Standard + AP_GROUPINFO_FLAGS("_ENABLE", 1, AP_WheelRateControl, _enabled, 0, AP_PARAM_FLAG_ENABLE), + + // @Param: _RATE_MAX + // @DisplayName: Wheel max rotation rate + // @Description: Wheel max rotation rate + // @Units: rad/s + // @Range: 0 200 + // @User: Standard + AP_GROUPINFO("_RATE_MAX", 2, AP_WheelRateControl, _rate_max, AP_WHEEL_RATE_MAX_DEFAULT), + + // @Param: _RATE_FF + // @DisplayName: Wheel rate control feed forward gain + // @Description: Wheel rate control feed forward gain. Desired rate (in radians/sec) is multiplied by this constant and output to output (in the range -1 to +1) + // @Range: 0.100 2.000 + // @User: Standard + + // @Param: _RATE_P + // @DisplayName: Wheel rate control P gain + // @Description: Wheel rate control P gain. Converts rate error (in radians/sec) to output (in the range -1 to +1) + // @Range: 0.100 2.000 + // @User: Standard + + // @Param: _RATE_I + // @DisplayName: Wheel rate control I gain + // @Description: Wheel rate control I gain. Corrects long term error between the desired rate (in rad/s) and actual + // @Range: 0.000 2.000 + // @User: Standard + + // @Param: _RATE_IMAX + // @DisplayName: Wheel rate control I gain maximum + // @Description: Wheel rate control I gain maximum. Constrains the output (range -1 to +1) that the I term will generate + // @Range: 0.000 1.000 + // @User: Standard + + // @Param: _RATE_D + // @DisplayName: Wheel rate control D gain + // @Description: Wheel rate control D gain. Compensates for short-term change in desired rate vs actual + // @Range: 0.000 0.400 + // @User: Standard + + // @Param: _RATE_FILT + // @DisplayName: Wheel rate control filter frequency + // @Description: Wheel rate control input filter. Lower values reduce noise but add delay. + // @Range: 1.000 100.000 + // @Units: Hz + // @User: Standard + AP_SUBGROUPINFO(_rate_pid0, "_RATE_", 3, AP_WheelRateControl, AC_PID), + + // @Param: 2_RATE_FF + // @DisplayName: Wheel rate control feed forward gain + // @Description: Wheel rate control feed forward gain. Desired rate (in radians/sec) is multiplied by this constant and output to output (in the range -1 to +1) + // @Range: 0.100 2.000 + // @User: Standard + + // @Param: 2_RATE_P + // @DisplayName: Wheel rate control P gain + // @Description: Wheel rate control P gain. Converts rate error (in radians/sec) to output (in the range -1 to +1) + // @Range: 0.100 2.000 + // @User: Standard + + // @Param: 2_RATE_I + // @DisplayName: Wheel rate control I gain + // @Description: Wheel rate control I gain. Corrects long term error between the desired rate (in rad/s) and actual + // @Range: 0.000 2.000 + // @User: Standard + + // @Param: 2_RATE_IMAX + // @DisplayName: Wheel rate control I gain maximum + // @Description: Wheel rate control I gain maximum. Constrains the output (range -1 to +1) that the I term will generate + // @Range: 0.000 1.000 + // @User: Standard + + // @Param: 2_RATE_D + // @DisplayName: Wheel rate control D gain + // @Description: Wheel rate control D gain. Compensates for short-term change in desired rate vs actual + // @Range: 0.000 0.400 + // @User: Standard + + // @Param: 2_RATE_FILT + // @DisplayName: Wheel rate control filter frequency + // @Description: Wheel rate control input filter. Lower values reduce noise but add delay. + // @Range: 1.000 100.000 + // @Units: Hz + // @User: Standard + AP_SUBGROUPINFO(_rate_pid1, "2_RATE_", 4, AP_WheelRateControl, AC_PID), + + AP_GROUPEND +}; + +AP_WheelRateControl::AP_WheelRateControl(const AP_WheelEncoder &wheel_encoder_ref) : + _wheel_encoder(wheel_encoder_ref) +{ + AP_Param::setup_object_defaults(this, var_info); +} + +// returns true if a wheel encoder and rate control PID are available for this instance +bool AP_WheelRateControl::enabled(uint8_t instance) +{ + // sanity check instance + if ((instance > 1) || (_enabled == 0)) { + return false; + } + // wheel encoder enabled + return _wheel_encoder.enabled(instance); +} + +// get throttle output in the range -100 to +100 given a desired rate expressed as a percentage of the rate_max (-100 to +100) +// instance can be 0 or 1 +float AP_WheelRateControl::get_rate_controlled_throttle(uint8_t instance, float desired_rate_pct, float dt) +{ + if (!enabled(instance)) { + return 0; + } + + // determine which PID instance to use + AC_PID& rate_pid = (instance == 0) ? _rate_pid0 : _rate_pid1; + + // set PID's dt + rate_pid.set_dt(dt); + + // check for timeout + uint32_t now = AP_HAL::millis(); + if (now - _last_update_ms > AP_WHEEL_RATE_CONTROL_TIMEOUT_MS) { + rate_pid.reset_filter(); + rate_pid.reset_I(); + _limit[instance].lower = false; + _limit[instance].upper = false; + } + _last_update_ms = now; + + // convert desired rate as a percentage to radians/sec + float desired_rate = desired_rate_pct / 100.0f * get_rate_max_rads(); + + // get actual rate from wheeel encoder + float actual_rate = _wheel_encoder.get_rate(instance); + + // calculate rate error and pass to pid controller + float rate_error = desired_rate - actual_rate; + rate_pid.set_input_filter_all(rate_error); + + // store desired and actual for logging purposes + rate_pid.set_desired_rate(desired_rate); + rate_pid.set_actual_rate(actual_rate); + + // get ff + float ff = rate_pid.get_ff(desired_rate); + + // get p + float p = rate_pid.get_p(); + + // get i unless we hit limit on last iteration + float i = rate_pid.get_integrator(); + if (((is_negative(rate_error) && !_limit[instance].lower) || (is_positive(rate_error) && !_limit[instance].upper))) { + i = rate_pid.get_i(); + } + + // get d + float d = rate_pid.get_d(); + + // constrain and set limit flags + float output = ff + p + i + d; + + // set limits for next iteration + _limit[instance].upper = output >= 100.0f; + _limit[instance].lower = output <= -100.0f; + + return output; +} + +// get pid objects for reporting +AC_PID& AP_WheelRateControl::get_pid(uint8_t instance) +{ + if (instance == 0) { + return _rate_pid0; + } else { + return _rate_pid0; + } +} diff --git a/libraries/AP_WheelEncoder/AP_WheelRateControl.h b/libraries/AP_WheelEncoder/AP_WheelRateControl.h new file mode 100644 index 0000000000..2d30b5bb04 --- /dev/null +++ b/libraries/AP_WheelEncoder/AP_WheelRateControl.h @@ -0,0 +1,73 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +#pragma once + +#include +#include +#include +#include +#include + +// wheel rate control defaults +#define AP_WHEEL_RATE_MAX_DEFAULT 12.0f // maximum wheel rotation rate in rad/sec (about 115rpm, 687deg/sec) +#define AP_WHEEL_RATE_CONTROL_FF 8.00f +#define AP_WHEEL_RATE_CONTROL_P 2.00f +#define AP_WHEEL_RATE_CONTROL_I 2.00f +#define AP_WHEEL_RATE_CONTROL_IMAX 1.00f +#define AP_WHEEL_RATE_CONTROL_D 0.01f +#define AP_WHEEL_RATE_CONTROL_FILT 0.00f +#define AP_WHEEL_RATE_CONTROL_DT 0.02f +#define AP_WHEEL_RATE_CONTROL_TIMEOUT_MS 200 + +class AP_WheelRateControl { + +public: + + AP_WheelRateControl(const AP_WheelEncoder &wheel_encoder_ref); + + // returns true if a wheel encoder and rate control PID are available for this instance + bool enabled(uint8_t instance); + + // get throttle output in the range -100 to +100 given a desired rate expressed as a percentage of the rate_max (-100 to +100) + // instance can be 0 or 1 + float get_rate_controlled_throttle(uint8_t instance, float desired_rate_pct, float dt); + + // get rate maximum in radians/sec + float get_rate_max_rads() const { return MAX(_rate_max, 0.0f); } + + // get pid objects for reporting + AC_PID& get_pid(uint8_t instance); + + static const struct AP_Param::GroupInfo var_info[]; + +private: + + // parameters + AP_Int8 _enabled; // top level enable/disable control + AP_Float _rate_max; // wheel maximum rotation rate in rad/s + AC_PID _rate_pid0 = AC_PID(AP_WHEEL_RATE_CONTROL_P, AP_WHEEL_RATE_CONTROL_I, AP_WHEEL_RATE_CONTROL_D, AP_WHEEL_RATE_CONTROL_IMAX, AP_WHEEL_RATE_CONTROL_FILT, AP_WHEEL_RATE_CONTROL_DT, AP_WHEEL_RATE_CONTROL_FF); + AC_PID _rate_pid1 = AC_PID(AP_WHEEL_RATE_CONTROL_P, AP_WHEEL_RATE_CONTROL_I, AP_WHEEL_RATE_CONTROL_D, AP_WHEEL_RATE_CONTROL_IMAX, AP_WHEEL_RATE_CONTROL_FILT, AP_WHEEL_RATE_CONTROL_DT, AP_WHEEL_RATE_CONTROL_FF); + + // limit flags + struct AP_MotorsUGV_limit { + bool lower; // reached this instance's lower limit on last iteration + bool upper; // reached this instance's upper limit on last iteration + } _limit[2]; + + // internal variables + const AP_WheelEncoder& _wheel_encoder; // pointer to accompanying wheel encoder + uint32_t _last_update_ms; // system time of last call to get_rate_controlled_throttle +};