APM:Libraries
AC_Loiter.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 #include "AC_Loiter.h"
3 
4 extern const AP_HAL::HAL& hal;
5 
6 #define LOITER_SPEED_DEFAULT 1250.0f // default loiter speed in cm/s
7 #define LOITER_SPEED_MIN 20.0f // minimum loiter speed in cm/s
8 #define LOITER_ACCEL_MAX_DEFAULT 500.0f // default acceleration in loiter mode
9 #define LOITER_BRAKE_ACCEL_DEFAULT 250.0f // minimum acceleration in loiter mode
10 #define LOITER_BRAKE_JERK_DEFAULT 500.0f // maximum jerk in cm/s/s/s in loiter mode
11 #define LOITER_BRAKE_START_DELAY_DEFAULT 1.0f // delay (in seconds) before loiter braking begins after sticks are released
12 #define LOITER_VEL_CORRECTION_MAX 200.0f // max speed used to correct position errors in loiter
13 #define LOITER_POS_CORRECTION_MAX 200.0f // max position error in loiter
14 #define LOITER_ACTIVE_TIMEOUT_MS 200 // loiter controller is considered active if it has been called within the past 200ms (0.2 seconds)
15 
17 
18  // @Param: ANG_MAX
19  // @DisplayName: Loiter Angle Max
20  // @Description: Loiter maximum lean angle. Set to zero for 2/3 of PSC_ANGLE_MAX or ANGLE_MAX
21  // @Units: deg
22  // @Range: 0 45
23  // @Increment: 1
24  // @User: Advanced
25  AP_GROUPINFO("ANG_MAX", 1, AC_Loiter, _angle_max, 0.0f),
26 
27  // @Param: SPEED
28  // @DisplayName: Loiter Horizontal Maximum Speed
29  // @Description: Defines the maximum speed in cm/s which the aircraft will travel horizontally while in loiter mode
30  // @Units: cm/s
31  // @Range: 20 2000
32  // @Increment: 50
33  // @User: Standard
34  AP_GROUPINFO("SPEED", 2, AC_Loiter, _speed_cms, LOITER_SPEED_DEFAULT),
35 
36  // @Param: ACC_MAX
37  // @DisplayName: Loiter maximum correction acceleration
38  // @Description: Loiter maximum correction acceleration in cm/s/s. Higher values cause the copter to correct position errors more aggressively.
39  // @Units: cm/s/s
40  // @Range: 100 981
41  // @Increment: 1
42  // @User: Advanced
43  AP_GROUPINFO("ACC_MAX", 3, AC_Loiter, _accel_cmss, LOITER_ACCEL_MAX_DEFAULT),
44 
45  // @Param: BRK_ACCEL
46  // @DisplayName: Loiter braking acceleration
47  // @Description: Loiter braking acceleration in cm/s/s. Higher values stop the copter more quickly when the stick is centered.
48  // @Units: cm/s/s
49  // @Range: 25 250
50  // @Increment: 1
51  // @User: Advanced
52  AP_GROUPINFO("BRK_ACCEL", 4, AC_Loiter, _brake_accel_cmss, LOITER_BRAKE_ACCEL_DEFAULT),
53 
54  // @Param: BRK_JERK
55  // @DisplayName: Loiter braking jerk
56  // @Description: Loiter braking jerk in cm/s/s/s. Higher values will remove braking faster if the pilot moves the sticks during a braking manuver.
57  // @Units: cm/s/s/s
58  // @Range: 500 5000
59  // @Increment: 1
60  // @User: Advanced
61  AP_GROUPINFO("BRK_JERK", 5, AC_Loiter, _brake_jerk_max_cmsss, LOITER_BRAKE_JERK_DEFAULT),
62 
63  // @Param: BRK_DELAY
64  // @DisplayName: Loiter brake start delay (in seconds)
65  // @Description: Loiter brake start delay (in seconds)
66  // @Units: s
67  // @Range: 0 2
68  // @Increment: 0.1
69  // @User: Advanced
70  AP_GROUPINFO("BRK_DELAY", 6, AC_Loiter, _brake_delay, LOITER_BRAKE_START_DELAY_DEFAULT),
71 
73 };
74 
75 // Default constructor.
76 // Note that the Vector/Matrix constructors already implicitly zero
77 // their values.
78 //
79 AC_Loiter::AC_Loiter(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control, const AC_AttitudeControl& attitude_control) :
80  _inav(inav),
81  _ahrs(ahrs),
82  _pos_control(pos_control),
83  _attitude_control(attitude_control)
84 {
86 }
87 
89 void AC_Loiter::init_target(const Vector3f& position)
90 {
92 
93  // initialise pos controller speed, acceleration
96 
97  // initialise desired acceleration and angles to zero to remain on station
101 
102  // set target position
103  _pos_control.set_xy_target(position.x, position.y);
104 
105  // set vehicle velocity and acceleration to zero
108 
109  // initialise position controller
111 }
112 
115 {
116  const Vector3f& curr_pos = _inav.get_position();
117  const Vector3f& curr_vel = _inav.get_velocity();
118 
120 
121  // initialise pos controller speed and acceleration
125 
126  // initialise desired acceleration based on the current velocity and the artificial drag
127  float pilot_acceleration_max = GRAVITY_MSS*100.0f * tanf(radians(get_angle_max_cd()*0.01f));
128  _predicted_accel.x = pilot_acceleration_max*curr_vel.x/_speed_cms;
129  _predicted_accel.y = pilot_acceleration_max*curr_vel.y/_speed_cms;
131  // this should be the current roll and pitch angle.
134 
135  // set target position
136  _pos_control.set_xy_target(curr_pos.x, curr_pos.y);
137 
138  // set vehicle velocity and acceleration to current state
139  _pos_control.set_desired_velocity_xy(curr_vel.x, curr_vel.y);
141 
142  // initialise position controller
144 }
145 
148 {
149  const Vector3f& curr_pos = _inav.get_position();
150 
151  // set target position to current position
152  _pos_control.set_xy_target(curr_pos.x, curr_pos.y);
153 }
154 
156 // dt should be the time (in seconds) since the last call to this function
157 void AC_Loiter::set_pilot_desired_acceleration(float euler_roll_angle_cd, float euler_pitch_angle_cd, float dt)
158 {
159  // Convert from centidegrees on public interface to radians
160  const float euler_roll_angle = radians(euler_roll_angle_cd*0.01f);
161  const float euler_pitch_angle = radians(euler_pitch_angle_cd*0.01f);
162 
163  // difference between where we think we should be and where we want to be
164  Vector2f angle_error(wrap_PI(euler_roll_angle - _predicted_euler_angle.x), wrap_PI(euler_pitch_angle - _predicted_euler_angle.y));
165 
166  // calculate the angular velocity that we would expect given our desired and predicted attitude
168 
169  // update our predicted attitude based on our predicted angular velocity
171 
172  // convert our desired attitude to an acceleration vector assuming we are hovering
173  const float pilot_cos_pitch_target = cosf(euler_pitch_angle);
174  const float pilot_accel_rgt_cms = GRAVITY_MSS*100.0f * tanf(euler_roll_angle)/pilot_cos_pitch_target;
175  const float pilot_accel_fwd_cms = -GRAVITY_MSS*100.0f * tanf(euler_pitch_angle);
176 
177  // convert our predicted attitude to an acceleration vector assuming we are hovering
178  const float pilot_predicted_cos_pitch_target = cosf(_predicted_euler_angle.y);
179  const float pilot_predicted_accel_rgt_cms = GRAVITY_MSS*100.0f * tanf(_predicted_euler_angle.x)/pilot_predicted_cos_pitch_target;
180  const float pilot_predicted_accel_fwd_cms = -GRAVITY_MSS*100.0f * tanf(_predicted_euler_angle.y);
181 
182  // rotate acceleration vectors input to lat/lon frame
183  _desired_accel.x = (pilot_accel_fwd_cms*_ahrs.cos_yaw() - pilot_accel_rgt_cms*_ahrs.sin_yaw());
184  _desired_accel.y = (pilot_accel_fwd_cms*_ahrs.sin_yaw() + pilot_accel_rgt_cms*_ahrs.cos_yaw());
185  _predicted_accel.x = (pilot_predicted_accel_fwd_cms*_ahrs.cos_yaw() - pilot_predicted_accel_rgt_cms*_ahrs.sin_yaw());
186  _predicted_accel.y = (pilot_predicted_accel_fwd_cms*_ahrs.sin_yaw() + pilot_predicted_accel_rgt_cms*_ahrs.cos_yaw());
187 }
188 
190 void AC_Loiter::get_stopping_point_xy(Vector3f& stopping_point) const
191 {
192  _pos_control.get_stopping_point_xy(stopping_point);
193 }
194 
197 {
198  if (is_zero(_angle_max)) {
200  }
202 }
203 
205 void AC_Loiter::update(float ekfGndSpdLimit, float ekfNavVelGainScaler)
206 {
207  // calculate dt
209  if (dt >= 0.2f) {
210  dt = 0.0f;
211  }
212 
213  // initialise pos controller speed and acceleration
216 
217  calc_desired_velocity(dt,ekfGndSpdLimit);
218  _pos_control.update_xy_controller(ekfNavVelGainScaler);
219 }
220 
221 // sanity check parameters
223 {
226 }
227 
230 void AC_Loiter::calc_desired_velocity(float nav_dt, float ekfGndSpdLimit)
231 {
232  // calculate a loiter speed limit which is the minimum of the value set by the LOITER_SPEED
233  // parameter and the value set by the EKF to observe optical flow limits
234  float gnd_speed_limit_cms = MIN(_speed_cms, ekfGndSpdLimit*100.0f);
235  gnd_speed_limit_cms = MAX(gnd_speed_limit_cms, LOITER_SPEED_MIN);
236 
237  float pilot_acceleration_max = GRAVITY_MSS*100.0f * tanf(radians(get_angle_max_cd()*0.01f));
238 
239  // range check nav_dt
240  if (nav_dt < 0) {
241  return;
242  }
243 
244  _pos_control.set_speed_xy(gnd_speed_limit_cms);
247 
248  // get loiters desired velocity from the position controller where it is being stored.
249  const Vector3f &desired_vel_3d = _pos_control.get_desired_velocity();
250  Vector2f desired_vel(desired_vel_3d.x,desired_vel_3d.y);
251 
252  // update the desired velocity using our predicted acceleration
253  desired_vel.x += _predicted_accel.x * nav_dt;
254  desired_vel.y += _predicted_accel.y * nav_dt;
255 
256  Vector2f loiter_accel_brake;
257  float desired_speed = desired_vel.length();
258  if (!is_zero(desired_speed)) {
259  Vector2f desired_vel_norm = desired_vel/desired_speed;
260 
261  // TODO: consider using a velocity squared relationship like
262  // pilot_acceleration_max*(desired_speed/gnd_speed_limit_cms)^2;
263  // the drag characteristic of a multirotor should be examined to generate a curve
264  // we could add a expo function here to fine tune it
265 
266  // calculate a drag acceleration based on the desired speed.
267  float drag_decel = pilot_acceleration_max*desired_speed/gnd_speed_limit_cms;
268 
269  // calculate a braking acceleration if sticks are at zero
270  float loiter_brake_accel = 0.0f;
271  if (_desired_accel.is_zero()) {
272  if ((AP_HAL::millis()-_brake_timer) > _brake_delay * 1000.0f) {
273  float brake_gain = _pos_control.get_vel_xy_pid().kP() * 0.5f;
274  loiter_brake_accel = constrain_float(AC_AttitudeControl::sqrt_controller(desired_speed, brake_gain, _brake_jerk_max_cmsss, nav_dt), 0.0f, _brake_accel_cmss);
275  }
276  } else {
277  loiter_brake_accel = 0.0f;
279  }
281  loiter_accel_brake = desired_vel_norm*_brake_accel;
282 
283  // update the desired velocity using the drag and braking accelerations
284  desired_speed = MAX(desired_speed-(drag_decel+_brake_accel)*nav_dt,0.0f);
285  desired_vel = desired_vel_norm*desired_speed;
286  }
287 
288  // add braking to the desired acceleration
289  _desired_accel -= loiter_accel_brake;
290 
291  // 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)
292  float horizSpdDem = desired_vel.length();
293  if (horizSpdDem > gnd_speed_limit_cms) {
294  desired_vel.x = desired_vel.x * gnd_speed_limit_cms / horizSpdDem;
295  desired_vel.y = desired_vel.y * gnd_speed_limit_cms / horizSpdDem;
296  }
297 
298  // Limit the velocity to prevent fence violations
299  // TODO: We need to also limit the _desired_accel
300  if (_avoid != nullptr) {
301  _avoid->adjust_velocity(_pos_control.get_pos_xy_p().kP(), _accel_cmss, desired_vel, nav_dt);
302  }
303 
304  // send adjusted feed forward acceleration and velocity back to the Position Controller
306  _pos_control.set_desired_velocity_xy(desired_vel.x, desired_vel.y);
307 }
void get_stopping_point_xy(Vector3f &stopping_point) const
void set_desired_velocity_xy(float vel_lat_cms, float vel_lon_cms)
float get_lean_angle_max_cd() const
get_lean_angle_max_cd - returns the maximum lean angle the autopilot may request
void input_shaping_rate_predictor(Vector2f error_angle, Vector2f &target_ang_vel, float dt) const
virtual const Vector3f & get_position() const =0
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
#define LOITER_VEL_CORRECTION_MAX
Definition: AC_Loiter.cpp:12
AC_P & get_pos_xy_p()
#define ToRad(x)
Definition: AP_Common.h:53
void set_desired_accel_xy(float accel_lat_cms, float accel_lon_cms)
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
#define LOITER_BRAKE_START_DELAY_DEFAULT
Definition: AC_Loiter.cpp:11
void update_xy_controller(float ekfNavVelGainScaler)
update_xy_controller - run the horizontal position controller - should be called at 100hz or higher ...
Vector2f _desired_accel
Definition: AC_Loiter.h:87
void set_leash_length_xy(float leash)
set the horizontal leash length
const AC_AttitudeControl & _attitude_control
Definition: AC_Loiter.h:75
void soften_for_landing()
reduce response for landing
Definition: AC_Loiter.cpp:147
void calc_desired_velocity(float nav_dt, float ekfGndSpdLimit)
Definition: AC_Loiter.cpp:230
#define MIN(a, b)
Definition: usb_conf.h:215
Vector2f _predicted_accel
Definition: AC_Loiter.h:88
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
AP_Float & kP()
Definition: AC_PID_2D.h:48
void set_xy_target(float x, float y)
set_xy_target in cm from home
void sanity_check_params()
Definition: AC_Loiter.cpp:222
AP_Float _brake_delay
Definition: AC_Loiter.h:84
T y
Definition: vector2.h:37
#define LOITER_SPEED_DEFAULT
Definition: AC_Loiter.cpp:6
AP_Float _speed_cms
Definition: AC_Loiter.h:80
float lean_angle_max() const
AC_Loiter(const AP_InertialNav &inav, const AP_AHRS_View &ahrs, AC_PosControl &pos_control, const AC_AttitudeControl &attitude_control)
Constructor.
Definition: AC_Loiter.cpp:79
void update(float ekfGndSpdLimit, float ekfNavVelGainScaler)
run the loiter controller
Definition: AC_Loiter.cpp:205
void get_stopping_point_xy(Vector3f &stopping_point) const
get vector to stopping point based on a horizontal position and velocity
Definition: AC_Loiter.cpp:190
float wrap_PI(const T radian)
Definition: AP_Math.cpp:152
static const struct AP_Param::GroupInfo var_info[]
Definition: AC_Loiter.h:60
const AP_InertialNav & _inav
Definition: AC_Loiter.h:72
#define LOITER_BRAKE_JERK_DEFAULT
Definition: AC_Loiter.cpp:10
#define GRAVITY_MSS
Definition: definitions.h:47
const AP_AHRS_View & _ahrs
Definition: AC_Loiter.h:73
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
Vector2f _predicted_euler_rate
Definition: AC_Loiter.h:90
void init_xy_controller(bool reset_I=true)
T y
Definition: vector3.h:67
uint32_t millis()
Definition: system.cpp:157
AC_PID_2D & get_vel_xy_pid()
static float sqrt_controller(float error, float p, float second_ord_lim, float dt)
AP_Float _angle_max
Definition: AC_Loiter.h:79
#define LOITER_POS_CORRECTION_MAX
Definition: AC_Loiter.cpp:13
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
#define LOITER_BRAKE_ACCEL_DEFAULT
Definition: AC_Loiter.cpp:9
Vector2f _predicted_euler_angle
Definition: AC_Loiter.h:89
AP_Float _brake_jerk_max_cmsss
Definition: AC_Loiter.h:83
float length(void) const
Definition: vector2.cpp:24
const Vector3f & get_desired_velocity()
get_desired_velocity - returns xy desired velocity (i.e. feed forward) in cm/s in lat and lon directi...
AP_Float _accel_cmss
Definition: AC_Loiter.h:81
void init_target()
initialize&#39;s position and feed-forward velocity from current pos and velocity
Definition: AC_Loiter.cpp:114
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
T x
Definition: vector2.h:37
#define LOITER_ACCEL_MAX_DEFAULT
Definition: AC_Loiter.cpp:8
static constexpr float radians(float deg)
Definition: AP_Math.h:158
void zero()
Definition: vector2.h:125
bool is_zero(void) const
Definition: vector2.h:105
void set_accel_xy(float accel_cmss)
set_accel_xy - set horizontal acceleration in cm/s/s
AP_Float _brake_accel_cmss
Definition: AC_Loiter.h:82
Vector3f get_att_target_euler_cd() const
AC_PosControl & _pos_control
Definition: AC_Loiter.h:74
void set_pilot_desired_acceleration(float euler_roll_angle_cd, float euler_pitch_angle_cd, float dt)
set pilot desired acceleration in centi-degrees
Definition: AC_Loiter.cpp:157
float time_since_last_xy_update() const
virtual const Vector3f & get_velocity() const =0
void adjust_velocity(float kP, float accel_cmss, Vector2f &desired_vel_cms, float dt)
Definition: AC_Avoid.cpp:63
float _brake_timer
Definition: AC_Loiter.h:91
void set_speed_xy(float speed_cms)
set_speed_xy - set horizontal speed maximum in cm/s
AC_Avoid * _avoid
Definition: AC_Loiter.h:76
AP_Float & kP()
Definition: AC_P.h:58
#define AP_GROUPEND
Definition: AP_Param.h:121
float _brake_accel
Definition: AC_Loiter.h:92
T x
Definition: vector3.h:67
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214
#define LOITER_SPEED_MIN
Definition: AC_Loiter.cpp:7
float get_angle_max_cd() const
get maximum lean angle when using loiter
Definition: AC_Loiter.cpp:196