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/AC_WPNav/AC_Loiter.cpp
Views: 1798
#include <AP_HAL/AP_HAL.h>1#include "AC_Loiter.h"2#include <AP_Vehicle/AP_Vehicle_Type.h>3#include <AC_Avoidance/AC_Avoid.h>45extern const AP_HAL::HAL& hal;67#define LOITER_SPEED_DEFAULT 1250.0f // default loiter speed in cm/s8#define LOITER_SPEED_MIN 20.0f // minimum loiter speed in cm/s9#define LOITER_ACCEL_MAX_DEFAULT 500.0f // default acceleration in loiter mode10#define LOITER_BRAKE_ACCEL_DEFAULT 250.0f // minimum acceleration in loiter mode11#define LOITER_BRAKE_JERK_DEFAULT 500.0f // maximum jerk in cm/s/s/s in loiter mode12#define LOITER_BRAKE_START_DELAY_DEFAULT 1.0f // delay (in seconds) before loiter braking begins after sticks are released13#define LOITER_VEL_CORRECTION_MAX 200.0f // max speed used to correct position errors in loiter14#define LOITER_POS_CORRECTION_MAX 200.0f // max position error in loiter15#define LOITER_ACTIVE_TIMEOUT_MS 200 // loiter controller is considered active if it has been called within the past 200ms (0.2 seconds)1617const AP_Param::GroupInfo AC_Loiter::var_info[] = {1819// @Param: ANG_MAX20// @DisplayName: Loiter pilot angle max21// @Description{Copter, Sub}: Loiter maximum pilot requested lean angle. Set to zero for 2/3 of PSC_ANGLE_MAX/ANGLE_MAX. The maximum vehicle lean angle is still limited by PSC_ANGLE_MAX/ANGLE_MAX22// @Description: Loiter maximum pilot requested lean angle. Set to zero for 2/3 of Q_P_ANGLE_MAX/Q_ANGLE_MAX. The maximum vehicle lean angle is still limited by Q_P_ANGLE_MAX/Q_ANGLE_MAX23// @Units: deg24// @Range: 0 4525// @Increment: 126// @User: Advanced27AP_GROUPINFO("ANG_MAX", 1, AC_Loiter, _angle_max, 0.0f),2829// @Param: SPEED30// @DisplayName: Loiter Horizontal Maximum Speed31// @Description: Defines the maximum speed in cm/s which the aircraft will travel horizontally while in loiter mode32// @Units: cm/s33// @Range: 20 350034// @Increment: 5035// @User: Standard36AP_GROUPINFO("SPEED", 2, AC_Loiter, _speed_cms, LOITER_SPEED_DEFAULT),3738// @Param: ACC_MAX39// @DisplayName: Loiter maximum correction acceleration40// @Description: Loiter maximum correction acceleration in cm/s/s. Higher values cause the copter to correct position errors more aggressively.41// @Units: cm/s/s42// @Range: 100 98143// @Increment: 144// @User: Advanced45AP_GROUPINFO("ACC_MAX", 3, AC_Loiter, _accel_cmss, LOITER_ACCEL_MAX_DEFAULT),4647// @Param: BRK_ACCEL48// @DisplayName: Loiter braking acceleration49// @Description: Loiter braking acceleration in cm/s/s. Higher values stop the copter more quickly when the stick is centered.50// @Units: cm/s/s51// @Range: 25 25052// @Increment: 153// @User: Advanced54AP_GROUPINFO("BRK_ACCEL", 4, AC_Loiter, _brake_accel_cmss, LOITER_BRAKE_ACCEL_DEFAULT),5556// @Param: BRK_JERK57// @DisplayName: Loiter braking jerk58// @Description: Loiter braking jerk in cm/s/s/s. Higher values will remove braking faster if the pilot moves the sticks during a braking maneuver.59// @Units: cm/s/s/s60// @Range: 500 500061// @Increment: 162// @User: Advanced63AP_GROUPINFO("BRK_JERK", 5, AC_Loiter, _brake_jerk_max_cmsss, LOITER_BRAKE_JERK_DEFAULT),6465// @Param: BRK_DELAY66// @DisplayName: Loiter brake start delay (in seconds)67// @Description: Loiter brake start delay (in seconds)68// @Units: s69// @Range: 0 270// @Increment: 0.171// @User: Advanced72AP_GROUPINFO("BRK_DELAY", 6, AC_Loiter, _brake_delay, LOITER_BRAKE_START_DELAY_DEFAULT),7374AP_GROUPEND75};7677// Default constructor.78// Note that the Vector/Matrix constructors already implicitly zero79// their values.80//81AC_Loiter::AC_Loiter(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control, const AC_AttitudeControl& attitude_control) :82_inav(inav),83_ahrs(ahrs),84_pos_control(pos_control),85_attitude_control(attitude_control)86{87AP_Param::setup_object_defaults(this, var_info);88}8990/// init_target to a position in cm from ekf origin91void AC_Loiter::init_target(const Vector2f& position)92{93sanity_check_params();9495// initialise position controller speed and acceleration96_pos_control.set_correction_speed_accel_xy(LOITER_VEL_CORRECTION_MAX, _accel_cmss);97_pos_control.set_pos_error_max_xy_cm(LOITER_POS_CORRECTION_MAX);9899// initialise position controller100_pos_control.init_xy_controller_stopping_point();101102// initialise desired acceleration and angles to zero to remain on station103_predicted_accel.zero();104_desired_accel.zero();105_predicted_euler_angle.zero();106_brake_accel = 0.0f;107108// set target position109_pos_control.set_pos_desired_xy_cm(position);110}111112/// initialize's position and feed-forward velocity from current pos and velocity113void AC_Loiter::init_target()114{115sanity_check_params();116117// initialise position controller speed and acceleration118_pos_control.set_correction_speed_accel_xy(LOITER_VEL_CORRECTION_MAX, _accel_cmss);119_pos_control.set_pos_error_max_xy_cm(LOITER_POS_CORRECTION_MAX);120121// initialise position controller and move target accelerations smoothly towards zero122_pos_control.relax_velocity_controller_xy();123124// initialise predicted acceleration and angles from the position controller125_predicted_accel = _pos_control.get_accel_target_cmss().xy();126_predicted_euler_angle.x = radians(_pos_control.get_roll_cd()*0.01f);127_predicted_euler_angle.y = radians(_pos_control.get_pitch_cd()*0.01f);128_brake_accel = 0.0f;129}130131/// reduce response for landing132void AC_Loiter::soften_for_landing()133{134_pos_control.soften_for_landing_xy();135}136137/// set pilot desired acceleration in centi-degrees138// dt should be the time (in seconds) since the last call to this function139void AC_Loiter::set_pilot_desired_acceleration(float euler_roll_angle_cd, float euler_pitch_angle_cd)140{141const float dt = _attitude_control.get_dt();142// Convert from centidegrees on public interface to radians143const float euler_roll_angle = radians(euler_roll_angle_cd * 0.01f);144const float euler_pitch_angle = radians(euler_pitch_angle_cd * 0.01f);145146// convert our desired attitude to an acceleration vector assuming we are not accelerating vertically147const Vector3f desired_euler {euler_roll_angle, euler_pitch_angle, _ahrs.yaw};148const Vector3f desired_accel = _pos_control.lean_angles_to_accel(desired_euler);149150_desired_accel.x = desired_accel.x;151_desired_accel.y = desired_accel.y;152153// difference between where we think we should be and where we want to be154Vector2f angle_error(wrap_PI(euler_roll_angle - _predicted_euler_angle.x), wrap_PI(euler_pitch_angle - _predicted_euler_angle.y));155156// calculate the angular velocity that we would expect given our desired and predicted attitude157_attitude_control.input_shaping_rate_predictor(angle_error, _predicted_euler_rate, dt);158159// update our predicted attitude based on our predicted angular velocity160_predicted_euler_angle += _predicted_euler_rate * dt;161162// convert our predicted attitude to an acceleration vector assuming we are not accelerating vertically163const Vector3f predicted_euler {_predicted_euler_angle.x, _predicted_euler_angle.y, _ahrs.yaw};164const Vector3f predicted_accel = _pos_control.lean_angles_to_accel(predicted_euler);165166_predicted_accel.x = predicted_accel.x;167_predicted_accel.y = predicted_accel.y;168}169170/// get vector to stopping point based on a horizontal position and velocity171void AC_Loiter::get_stopping_point_xy(Vector2f& stopping_point) const172{173Vector2p stop;174_pos_control.get_stopping_point_xy_cm(stop);175stopping_point = stop.tofloat();176}177178/// get maximum lean angle when using loiter179float AC_Loiter::get_angle_max_cd() const180{181if (!is_positive(_angle_max)) {182return MIN(_attitude_control.lean_angle_max_cd(), _pos_control.get_lean_angle_max_cd()) * (2.0f/3.0f);183}184return MIN(_angle_max*100.0f, _pos_control.get_lean_angle_max_cd());185}186187/// run the loiter controller188void AC_Loiter::update(bool avoidance_on)189{190calc_desired_velocity(avoidance_on);191_pos_control.update_xy_controller();192}193194// sanity check parameters195void AC_Loiter::sanity_check_params()196{197_speed_cms.set(MAX(_speed_cms, LOITER_SPEED_MIN));198_accel_cmss.set(MIN(_accel_cmss, GRAVITY_MSS * 100.0f * tanf(ToRad(_attitude_control.lean_angle_max_cd() * 0.01f))));199}200201/// calc_desired_velocity - updates desired velocity (i.e. feed forward) with pilot requested acceleration and fake wind resistance202/// updated velocity sent directly to position controller203void AC_Loiter::calc_desired_velocity(bool avoidance_on)204{205float ekfGndSpdLimit, ahrsControlScaleXY;206AP::ahrs().getControlLimits(ekfGndSpdLimit, ahrsControlScaleXY);207208const float dt = _pos_control.get_dt();209210// calculate a loiter speed limit which is the minimum of the value set by the LOITER_SPEED211// parameter and the value set by the EKF to observe optical flow limits212float gnd_speed_limit_cms = MIN(_speed_cms, ekfGndSpdLimit * 100.0f);213gnd_speed_limit_cms = MAX(gnd_speed_limit_cms, LOITER_SPEED_MIN);214215float pilot_acceleration_max = angle_to_accel(get_angle_max_cd() * 0.01) * 100;216217// range check dt218if (is_negative(dt)) {219return;220}221222// get loiters desired velocity from the position controller where it is being stored.223Vector2f desired_vel = _pos_control.get_vel_desired_cms().xy();224225// update the desired velocity using our predicted acceleration226desired_vel += _predicted_accel * dt;227228Vector2f loiter_accel_brake;229float desired_speed = desired_vel.length();230if (!is_zero(desired_speed)) {231Vector2f desired_vel_norm = desired_vel / desired_speed;232233// calculate a drag acceleration based on the desired speed.234float drag_decel = pilot_acceleration_max * desired_speed / gnd_speed_limit_cms;235236// calculate a braking acceleration if sticks are at zero237float loiter_brake_accel = 0.0f;238if (_desired_accel.is_zero()) {239if ((AP_HAL::millis() - _brake_timer) > _brake_delay * 1000.0f) {240float brake_gain = _pos_control.get_vel_xy_pid().kP() * 0.5f;241loiter_brake_accel = constrain_float(sqrt_controller(desired_speed, brake_gain, _brake_jerk_max_cmsss, dt), 0.0f, _brake_accel_cmss);242}243} else {244loiter_brake_accel = 0.0f;245_brake_timer = AP_HAL::millis();246}247_brake_accel += constrain_float(loiter_brake_accel - _brake_accel, -_brake_jerk_max_cmsss * dt, _brake_jerk_max_cmsss * dt);248loiter_accel_brake = desired_vel_norm * _brake_accel;249250// update the desired velocity using the drag and braking accelerations251desired_speed = MAX(desired_speed - (drag_decel + _brake_accel) * dt, 0.0f);252desired_vel = desired_vel_norm * desired_speed;253}254255// add braking to the desired acceleration256_desired_accel -= loiter_accel_brake;257258// Apply EKF limit to desired velocity - this limit is calculated by the EKF and adjusted as required to ensure certain sensor limits are respected (eg optical flow sensing)259float horizSpdDem = desired_vel.length();260if (horizSpdDem > gnd_speed_limit_cms) {261desired_vel = desired_vel * gnd_speed_limit_cms / horizSpdDem;262}263264#if AP_AVOIDANCE_ENABLED && !APM_BUILD_TYPE(APM_BUILD_ArduPlane)265if (avoidance_on) {266// Limit the velocity to prevent fence violations267// TODO: We need to also limit the _desired_accel268AC_Avoid *_avoid = AP::ac_avoid();269if (_avoid != nullptr) {270Vector3f avoidance_vel_3d{desired_vel.x, desired_vel.y, 0.0f};271_avoid->adjust_velocity(avoidance_vel_3d, _pos_control.get_pos_xy_p().kP(), _accel_cmss, _pos_control.get_pos_z_p().kP(), _pos_control.get_max_accel_z_cmss(), dt);272desired_vel = Vector2f{avoidance_vel_3d.x, avoidance_vel_3d.y};273}274}275#endif // !APM_BUILD_ArduPlane276277// get loiters desired velocity from the position controller where it is being stored.278Vector2p desired_pos = _pos_control.get_pos_desired_cm().xy();279280// update the desired position using our desired velocity and acceleration281desired_pos += (desired_vel * dt).topostype();282283// send adjusted feed forward acceleration and velocity back to the Position Controller284_pos_control.set_pos_vel_accel_xy(desired_pos, desired_vel, _desired_accel);285}286287288