Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/APM_Control/AR_PosControl.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415#include "AR_PosControl.h"1617#include <AP_HAL/AP_HAL.h>18#include <AP_Math/AP_Math.h>19#include <AP_AHRS/AP_AHRS.h>20#include <AP_Logger/AP_Logger.h>21#include <GCS_MAVLink/GCS.h>22#include <AC_Avoidance/AC_Avoid.h>23#include <AC_AttitudeControl/AC_PosControl.h>2425#define AR_POSCON_TIMEOUT_MS 100 // timeout after 0.1 sec26#define AR_POSCON_POS_P 0.2f // default position P gain27#define AR_POSCON_VEL_P 1.0f // default velocity P gain28#define AR_POSCON_VEL_I 0.0f // default velocity I gain29#define AR_POSCON_VEL_D 0.0f // default velocity D gain30#define AR_POSCON_VEL_FF 0.0f // default velocity FF gain31#define AR_POSCON_VEL_IMAX 1.0f // default velocity IMAX32#define AR_POSCON_VEL_FILT 5.0f // default velocity filter33#define AR_POSCON_VEL_FILT_D 5.0f // default velocity D term filter34#define AR_POSCON_DT 0.02f // default dt for PID controllers3536extern const AP_HAL::HAL& hal;3738AR_PosControl *AR_PosControl::_singleton;3940const AP_Param::GroupInfo AR_PosControl::var_info[] = {4142// @Param: _POS_P43// @DisplayName: Position controller P gain44// @Description: Position controller P gain. Converts the distance to the target location into a desired speed which is then passed to the loiter latitude rate controller45// @Range: 0.500 2.00046// @User: Standard47AP_SUBGROUPINFO(_p_pos, "_POS_", 1, AR_PosControl, AC_P_2D),4849// @Param: _VEL_P50// @DisplayName: Velocity (horizontal) P gain51// @Description: Velocity (horizontal) P gain. Converts the difference between desired and actual velocity to a target acceleration52// @Range: 0.1 6.053// @Increment: 0.154// @User: Advanced5556// @Param: _VEL_I57// @DisplayName: Velocity (horizontal) I gain58// @Description: Velocity (horizontal) I gain. Corrects long-term difference between desired and actual velocity to a target acceleration59// @Range: 0.00 1.0060// @Increment: 0.0161// @User: Advanced6263// @Param: _VEL_D64// @DisplayName: Velocity (horizontal) D gain65// @Description: Velocity (horizontal) D gain. Corrects short-term changes in velocity66// @Range: 0.00 1.0067// @Increment: 0.00168// @User: Advanced6970// @Param: _VEL_IMAX71// @DisplayName: Velocity (horizontal) integrator maximum72// @Description: Velocity (horizontal) integrator maximum. Constrains the target acceleration that the I gain will output73// @Range: 0 450074// @Increment: 1075// @Units: cm/s/s76// @User: Advanced7778// @Param: _VEL_FLTE79// @DisplayName: Velocity (horizontal) input filter80// @Description: Velocity (horizontal) input filter. This filter (in Hz) is applied to the input for P and I terms81// @Range: 0 10082// @Units: Hz83// @User: Advanced8485// @Param: _VEL_FLTD86// @DisplayName: Velocity (horizontal) input filter87// @Description: Velocity (horizontal) input filter. This filter (in Hz) is applied to the input for D term88// @Range: 0 10089// @Units: Hz90// @User: Advanced9192// @Param: _VEL_FF93// @DisplayName: Velocity (horizontal) feed forward gain94// @Description: Velocity (horizontal) feed forward gain. Converts the difference between desired velocity to a target acceleration95// @Range: 0 696// @Increment: 0.0197// @User: Advanced98AP_SUBGROUPINFO(_pid_vel, "_VEL_", 2, AR_PosControl, AC_PID_2D),99100AP_GROUPEND101};102103AR_PosControl::AR_PosControl(AR_AttitudeControl& atc) :104_atc(atc),105_p_pos(AR_POSCON_POS_P),106_pid_vel(AR_POSCON_VEL_P, AR_POSCON_VEL_I, AR_POSCON_VEL_D, AR_POSCON_VEL_FF, AR_POSCON_VEL_IMAX, AR_POSCON_VEL_FILT, AR_POSCON_VEL_FILT_D)107{108_singleton = this;109AP_Param::setup_object_defaults(this, var_info);110}111112// update navigation113void AR_PosControl::update(float dt)114{115// exit immediately if no current location, destination or disarmed116Vector2f curr_pos_NE;117Vector3f curr_vel_NED;118if (!hal.util->get_soft_armed() || !AP::ahrs().get_relative_position_NE_origin(curr_pos_NE) ||119!AP::ahrs().get_velocity_NED(curr_vel_NED)) {120_desired_speed = _atc.get_desired_speed_accel_limited(0.0f, dt);121_desired_lat_accel = 0.0f;122_desired_turn_rate_rads = 0.0f;123return;124}125126// check for ekf xy position reset127handle_ekf_xy_reset();128129// if no recent calls reset velocity controller130if (!is_active()) {131_pid_vel.reset_I();132_pid_vel.reset_filter();133}134_last_update_ms = AP_HAL::millis();135136// calculate position error and convert to desired velocity137_vel_target.zero();138if (_pos_target_valid) {139Vector2p pos_target = _pos_target;140_vel_target = _p_pos.update_all(pos_target.x, pos_target.y, curr_pos_NE);141}142143// calculation velocity error144bool stopping = false;145if (_vel_desired_valid) {146// add target velocity to desired velocity from position error147_vel_target += _vel_desired;148stopping = _vel_desired.is_zero();149}150151// limit velocity to maximum speed152_vel_target.limit_length(get_speed_max());153154// Limit the velocity to prevent fence violations155bool backing_up = false;156#if AP_AVOIDANCE_ENABLED157AC_Avoid *avoid = AP::ac_avoid();158if (avoid != nullptr) {159Vector3f vel_3d_cms{_vel_target.x * 100.0f, _vel_target.y * 100.0f, 0.0f};160const float accel_max_cmss = MIN(_accel_max, _lat_accel_max) * 100.0;161avoid->adjust_velocity(vel_3d_cms, backing_up, _p_pos.kP(), accel_max_cmss, _p_pos.kP(), accel_max_cmss, dt);162_vel_target.x = vel_3d_cms.x * 0.01;163_vel_target.y = vel_3d_cms.y * 0.01;164}165#endif // AP_AVOIDANCE_ENABLED166167// calculate limit vector based on steering limits168Vector2f steering_limit_vec;169if (_atc.steering_limit_left()) {170steering_limit_vec = AP::ahrs().body_to_earth2D(Vector2f{0, _reversed ? 1.0f : -1.0f});171} else if (_atc.steering_limit_right()) {172steering_limit_vec = AP::ahrs().body_to_earth2D(Vector2f{0, _reversed ? -1.0f : 1.0f});173}174175// calculate desired acceleration176_accel_target = _pid_vel.update_all(_vel_target, curr_vel_NED.xy(), dt, steering_limit_vec);177if (_accel_desired_valid) {178_accel_target += _accel_desired;179}180// velocity controller I-term zeroed in forward-back direction181const Vector2f lat_vec_ef = AP::ahrs().body_to_earth2D(Vector2f{0, 1});182const Vector2f vel_i = _pid_vel.get_i().projected(lat_vec_ef);183_pid_vel.set_integrator(vel_i);184185// convert desired acceleration to desired forward-back speed, desired lateral speed and desired turn rate186187// rotate acceleration into body frame using current heading188const Vector2f accel_target_FR = AP::ahrs().earth_to_body2D(_accel_target);189190// calculate minimum turn speed which is the max speed the vehicle could turn through the corner191// given the vehicle's turn radius and half its max lateral acceleration192// todo: remove MAX of zero when safe_sqrt fixed193float turn_speed_min = MAX(safe_sqrt(_atc.get_turn_lat_accel_max() * 0.5 * _turn_radius), 0);194195// rotate target velocity from earth-frame to body frame196const Vector2f vel_target_FR = AP::ahrs().earth_to_body2D(_vel_target);197198// desired speed is normally the forward component (only) of the target velocity199float des_speed = vel_target_FR.x;200if (!stopping) {201// do not let target speed fall below the minimum turn speed unless the vehicle is slowing down202const float abs_des_speed_min = MIN(_vel_target.length(), turn_speed_min);203if (_reversed != backing_up) {204// if reversed or backing up desired speed will be negative205des_speed = MIN(-abs_des_speed_min, vel_target_FR.x);206} else {207des_speed = MAX(abs_des_speed_min, vel_target_FR.x);208}209}210_desired_speed = _atc.get_desired_speed_accel_limited(des_speed, dt);211212// calculate turn rate from desired lateral acceleration213_desired_lat_accel = stopping ? 0 : accel_target_FR.y;214_desired_turn_rate_rads = _atc.get_turn_rate_from_lat_accel(_desired_lat_accel, _desired_speed);215}216217// true if update has been called recently218bool AR_PosControl::is_active() const219{220return ((AP_HAL::millis() - _last_update_ms) < AR_POSCON_TIMEOUT_MS);221}222223// set limits224void AR_PosControl::set_limits(float speed_max, float accel_max, float lat_accel_max, float jerk_max)225{226_speed_max = MAX(speed_max, 0);227_accel_max = MAX(accel_max, 0);228_lat_accel_max = MAX(lat_accel_max, 0);229_jerk_max = MAX(jerk_max, 0);230231// set position P controller limits232_p_pos.set_limits(_speed_max, MIN(_accel_max, _lat_accel_max), _jerk_max);233}234235// setter to allow vehicle code to provide turn related param values to this library (should be updated regularly)236void AR_PosControl::set_turn_params(float turn_radius, bool pivot_possible)237{238if (pivot_possible) {239_turn_radius = 0;240} else {241_turn_radius = turn_radius;242}243}244245// initialise the position controller to the current position, velocity, acceleration and attitude246// this should be called before the input shaping methods are used247bool AR_PosControl::init()248{249// get current position and velocity from AHRS250Vector2f pos_NE;251Vector3f vel_NED;252if (!AP::ahrs().get_relative_position_NE_origin(pos_NE) || !AP::ahrs().get_velocity_NED(vel_NED)) {253return false;254}255256// set target position to current position257_pos_target.x = pos_NE.x;258_pos_target.y = pos_NE.y;259260// set target velocity and acceleration261_vel_desired = vel_NED.xy();262_vel_target.zero();263_accel_desired = AP::ahrs().get_accel_ef().xy();264_accel_target.zero();265266// clear reversed setting267_reversed = false;268269// initialise ekf xy reset handler270init_ekf_xy_reset();271272return true;273}274275// adjust position, velocity and acceleration targets smoothly using input shaping276// pos is the target position as an offset from the EKF origin (in meters)277// vel is the target velocity in m/s. accel is the target acceleration in m/s/s278// dt should be the update rate in seconds279// init should be called once before starting to use these methods280void AR_PosControl::input_pos_target(const Vector2p &pos, float dt)281{282Vector2f vel;283Vector2f accel;284input_pos_vel_accel_target(pos, vel, accel, dt);285}286287// adjust position, velocity and acceleration targets smoothly using input shaping288// pos is the target position as an offset from the EKF origin (in meters)289// vel is the target velocity in m/s. accel is the target acceleration in m/s/s290// dt should be the update rate in seconds291// init should be called once before starting to use these methods292void AR_PosControl::input_pos_vel_target(const Vector2p &pos, const Vector2f &vel, float dt)293{294Vector2f accel;295input_pos_vel_accel_target(pos, vel, accel, dt);296}297298// adjust position, velocity and acceleration targets smoothly using input shaping299// pos is the target position as an offset from the EKF origin (in meters)300// vel is the target velocity in m/s. accel is the target acceleration in m/s/s301// dt should be the update rate in seconds302// init should be called once before starting to use these methods303void AR_PosControl::input_pos_vel_accel_target(const Vector2p &pos, const Vector2f &vel, const Vector2f &accel, float dt)304{305// adjust target position, velocity and acceleration forward by dt306update_pos_vel_accel_xy(_pos_target, _vel_desired, _accel_desired, dt, Vector2f(), Vector2f(), Vector2f());307308// call shape_pos_vel_accel_xy to pull target towards final destination309const float accel_max = MIN(_accel_max, _lat_accel_max);310shape_pos_vel_accel_xy(pos, vel, accel, _pos_target, _vel_desired, _accel_desired,311_speed_max, accel_max, _jerk_max, dt, false);312313// set flags so update will consume target position, desired velocity and desired acceleration314_pos_target_valid = true;315_vel_desired_valid = true;316_accel_desired_valid = true;317}318319// set target position, desired velocity and acceleration. These should be from an externally created path and are not "input shaped"320void AR_PosControl::set_pos_vel_accel_target(const Vector2p &pos, const Vector2f &vel, const Vector2f &accel)321{322_pos_target = pos;323_vel_desired = vel;324_accel_desired = accel;325_pos_target_valid = true;326_vel_desired_valid = true;327_accel_desired_valid = true;328}329330// returns desired velocity vector (i.e. feed forward) in cm/s in lat and lon direction331Vector2f AR_PosControl::get_desired_velocity() const332{333if (_vel_desired_valid) {334return _vel_desired;335}336return Vector2f();337}338339// return desired acceleration vector in m/s in lat and lon direction340Vector2f AR_PosControl::get_desired_accel() const341{342if (_accel_desired_valid) {343return _accel_desired;344}345return Vector2f();346}347348/// get position error as a vector from the current position to the target position349Vector2p AR_PosControl::get_pos_error() const350{351// return zero error is not active or no position estimate352Vector2f curr_pos_NE;353if (!is_active() ||!AP::ahrs().get_relative_position_NE_origin(curr_pos_NE)) {354return Vector2p{};355}356357// get current position358return (_pos_target - curr_pos_NE.topostype());359}360361// get the slew rate value for velocity. used for oscillation detection in lua scripts362void AR_PosControl::get_srate(float &velocity_srate)363{364// slew rate is the same for x and y axis365velocity_srate = _pid_vel.get_pid_info_x().slew_rate;366}367368#if HAL_LOGGING_ENABLED369// write PSC logs370void AR_PosControl::write_log()371{372// exit immediately if not active373if (!is_active()) {374return;375}376377// exit immediately if no position or velocity estimate378Vector3f curr_pos_NED;379Vector3f curr_vel_NED;380if (!AP::ahrs().get_relative_position_NED_origin(curr_pos_NED) || !AP::ahrs().get_velocity_NED(curr_vel_NED)) {381return;382}383384// get acceleration385const Vector3f curr_accel_NED = AP::ahrs().get_accel_ef() * 100.0;386387// convert position to required format388Vector2f pos_target_2d_cm = get_pos_target().tofloat() * 100.0;389390// reuse logging from AC_PosControl:391AC_PosControl::Write_PSCN(0.0, // position desired392pos_target_2d_cm.x, // position target393curr_pos_NED.x * 100.0, // position394_vel_desired.x * 100.0, // desired velocity395_vel_target.x * 100.0, // target velocity396curr_vel_NED.x * 100.0, // velocity397_accel_desired.x * 100.0, // desired accel398_accel_target.x * 100.0, // target accel399curr_accel_NED.x); // accel400AC_PosControl::Write_PSCE(0.0, // position desired401pos_target_2d_cm.y, // position target402curr_pos_NED.y * 100.0, // position403_vel_desired.y * 100.0, // desired velocity404_vel_target.y * 100.0, // target velocity405curr_vel_NED.y * 100.0, // velocity406_accel_desired.y * 100.0, // desired accel407_accel_target.y * 100.0, // target accel408curr_accel_NED.y); // accel409}410#endif411412/// initialise ekf xy position reset check413void AR_PosControl::init_ekf_xy_reset()414{415Vector2f pos_shift;416_ekf_xy_reset_ms = AP::ahrs().getLastPosNorthEastReset(pos_shift);417}418419/// handle_ekf_xy_reset - check for ekf position reset and adjust loiter or brake target position420void AR_PosControl::handle_ekf_xy_reset()421{422// check for position shift423Vector2f pos_shift;424uint32_t reset_ms = AP::ahrs().getLastPosNorthEastReset(pos_shift);425if (reset_ms != _ekf_xy_reset_ms) {426Vector2f pos_NE;427if (!AP::ahrs().get_relative_position_NE_origin(pos_NE)) {428return;429}430_pos_target = (pos_NE + _p_pos.get_error()).topostype();431432Vector3f vel_NED;433if (!AP::ahrs().get_velocity_NED(vel_NED)) {434return;435}436_vel_desired = vel_NED.xy() + _pid_vel.get_error();437438_ekf_xy_reset_ms = reset_ms;439}440}441442443