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.h
Views: 1798
#pragma once12#include <AP_Common/AP_Common.h>3#include <APM_Control/AR_AttitudeControl.h>4#include <AC_PID/AC_P_2D.h> // P library (2-axis)5#include <AC_PID/AC_PID_2D.h> // PID library (2-axis)67class AR_PosControl {8public:910// constructor11AR_PosControl(AR_AttitudeControl& atc);1213// do not allow copying14CLASS_NO_COPY(AR_PosControl);1516static AR_PosControl *get_singleton() { return _singleton; }1718// update navigation19void update(float dt);2021// true if update has been called recently22bool is_active() const;2324// set speed, acceleration and jerk limits25void set_limits(float speed_max, float accel_max, float lat_accel_max, float jerk_max);2627// setter to allow vehicle code to provide turn related param values to this library (should be updated regularly)28void set_turn_params(float turn_radius, bool pivot_possible);2930// set reversed31void set_reversed(bool reversed) { _reversed = reversed; }3233// accessor for _reversed34bool get_reversed() { return _reversed; }3536// get limits37float get_speed_max() const { return _speed_max; }38float get_accel_max() const { return _accel_max; }39float get_lat_accel_max() const { return _lat_accel_max; }40float get_jerk_max() const { return _jerk_max; }4142// initialise the position controller to the current position, velocity, acceleration and attitude43// this should be called before the input shaping methods are used44// return true on success, false if targets cannot be initialised45bool init();4647// adjust position, velocity and acceleration targets smoothly using input shaping48// pos is the target position as an offset from the EKF origin (in meters)49// vel is the target velocity in m/s. accel is the target acceleration in m/s/s50// dt should be the update rate in seconds51// init should be called once before starting to use these methods52void input_pos_target(const Vector2p &pos, float dt);53void input_pos_vel_target(const Vector2p &pos, const Vector2f &vel, float dt);54void input_pos_vel_accel_target(const Vector2p &pos, const Vector2f &vel, const Vector2f &accel, float dt);5556// set target position, desired velocity and acceleration. These should be from an externally created path and are not "input shaped"57void set_pos_vel_accel_target(const Vector2p &pos, const Vector2f &vel, const Vector2f &accel);5859// get outputs for forward-back speed (in m/s), lateral speed (in m/s) and turn rate (in rad/sec)60float get_desired_speed() const { return _desired_speed; }61float get_desired_turn_rate_rads() const { return _desired_turn_rate_rads; }62float get_desired_lat_accel() const { return _desired_lat_accel; }6364// get position target65const Vector2p& get_pos_target() const { return _pos_target; }6667// returns desired velocity vector (i.e. feed forward) in m/s in NE frame68Vector2f get_desired_velocity() const;6970// return desired acceleration vector in m/s in NE frame71Vector2f get_desired_accel() const;7273/// get position error as a vector from the current position to the target position74Vector2p get_pos_error() const;7576// get pid controllers77AC_P_2D& get_pos_p() { return _p_pos; }78AC_PID_2D& get_vel_pid() { return _pid_vel; }7980// get the slew rate value for velocity. used for oscillation detection in lua scripts81void get_srate(float &velocity_srate);8283// write PSC logs84void write_log();8586// parameter var table87static const struct AP_Param::GroupInfo var_info[];8889private:9091static AR_PosControl *_singleton;9293// initialise and check for ekf position resets94void init_ekf_xy_reset();95void handle_ekf_xy_reset();9697// references98AR_AttitudeControl &_atc; // rover attitude control library99100// parameters101AC_P_2D _p_pos; // position P controller to convert distance error to desired velocity102AC_PID_2D _pid_vel; // velocity PID controller to convert velocity error to desired acceleration103104// limits105float _speed_max; // maximum forward speed in m/s106float _accel_max; // maximum forward/back acceleration in m/s/s107float _lat_accel_max; // lateral acceleration maximum in m/s/s108float _jerk_max; // maximum jerk in m/s/s/s (used for both forward and lateral input shaping)109float _turn_radius; // vehicle turn radius in meters110111// position and velocity targets112Vector2p _pos_target; // position target as an offset (in meters) from the EKF origin113Vector2f _vel_desired; // desired velocity in m/s in NE frame. This is the "feed forward" provided by SCurves114Vector2f _vel_target; // velocity target in m/s in NE frame115Vector2f _accel_desired; // desired accel in m/s/s in NE frame. This is the "feed forward" provided by SCurves116Vector2f _accel_target; // accel target in m/s/s in NE frame117bool _pos_target_valid; // true if _pos_target is valid118bool _vel_desired_valid; // true if _vel_desired is valid119bool _accel_desired_valid; // true if _accel_desired is valid120121// variables for navigation122uint32_t _last_update_ms; // system time of last call to update123bool _reversed; // true if vehicle should move in reverse towards target124125// main outputs126float _desired_speed; // desired forward_back speed in m/s127float _desired_turn_rate_rads; // desired turn-rate in rad/sec (negative is counter clockwise, positive is clockwise)128float _desired_lat_accel; // desired lateral acceleration (for reporting only)129130// ekf reset handling131uint32_t _ekf_xy_reset_ms; // system time of last recorded ekf xy position reset132};133134135