CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AC_WPNav/AC_Loiter.cpp
Views: 1798
1
#include <AP_HAL/AP_HAL.h>
2
#include "AC_Loiter.h"
3
#include <AP_Vehicle/AP_Vehicle_Type.h>
4
#include <AC_Avoidance/AC_Avoid.h>
5
6
extern const AP_HAL::HAL& hal;
7
8
#define LOITER_SPEED_DEFAULT 1250.0f // default loiter speed in cm/s
9
#define LOITER_SPEED_MIN 20.0f // minimum loiter speed in cm/s
10
#define LOITER_ACCEL_MAX_DEFAULT 500.0f // default acceleration in loiter mode
11
#define LOITER_BRAKE_ACCEL_DEFAULT 250.0f // minimum acceleration in loiter mode
12
#define LOITER_BRAKE_JERK_DEFAULT 500.0f // maximum jerk in cm/s/s/s in loiter mode
13
#define LOITER_BRAKE_START_DELAY_DEFAULT 1.0f // delay (in seconds) before loiter braking begins after sticks are released
14
#define LOITER_VEL_CORRECTION_MAX 200.0f // max speed used to correct position errors in loiter
15
#define LOITER_POS_CORRECTION_MAX 200.0f // max position error in loiter
16
#define LOITER_ACTIVE_TIMEOUT_MS 200 // loiter controller is considered active if it has been called within the past 200ms (0.2 seconds)
17
18
const AP_Param::GroupInfo AC_Loiter::var_info[] = {
19
20
// @Param: ANG_MAX
21
// @DisplayName: Loiter pilot angle max
22
// @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_MAX
23
// @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_MAX
24
// @Units: deg
25
// @Range: 0 45
26
// @Increment: 1
27
// @User: Advanced
28
AP_GROUPINFO("ANG_MAX", 1, AC_Loiter, _angle_max, 0.0f),
29
30
// @Param: SPEED
31
// @DisplayName: Loiter Horizontal Maximum Speed
32
// @Description: Defines the maximum speed in cm/s which the aircraft will travel horizontally while in loiter mode
33
// @Units: cm/s
34
// @Range: 20 3500
35
// @Increment: 50
36
// @User: Standard
37
AP_GROUPINFO("SPEED", 2, AC_Loiter, _speed_cms, LOITER_SPEED_DEFAULT),
38
39
// @Param: ACC_MAX
40
// @DisplayName: Loiter maximum correction acceleration
41
// @Description: Loiter maximum correction acceleration in cm/s/s. Higher values cause the copter to correct position errors more aggressively.
42
// @Units: cm/s/s
43
// @Range: 100 981
44
// @Increment: 1
45
// @User: Advanced
46
AP_GROUPINFO("ACC_MAX", 3, AC_Loiter, _accel_cmss, LOITER_ACCEL_MAX_DEFAULT),
47
48
// @Param: BRK_ACCEL
49
// @DisplayName: Loiter braking acceleration
50
// @Description: Loiter braking acceleration in cm/s/s. Higher values stop the copter more quickly when the stick is centered.
51
// @Units: cm/s/s
52
// @Range: 25 250
53
// @Increment: 1
54
// @User: Advanced
55
AP_GROUPINFO("BRK_ACCEL", 4, AC_Loiter, _brake_accel_cmss, LOITER_BRAKE_ACCEL_DEFAULT),
56
57
// @Param: BRK_JERK
58
// @DisplayName: Loiter braking jerk
59
// @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.
60
// @Units: cm/s/s/s
61
// @Range: 500 5000
62
// @Increment: 1
63
// @User: Advanced
64
AP_GROUPINFO("BRK_JERK", 5, AC_Loiter, _brake_jerk_max_cmsss, LOITER_BRAKE_JERK_DEFAULT),
65
66
// @Param: BRK_DELAY
67
// @DisplayName: Loiter brake start delay (in seconds)
68
// @Description: Loiter brake start delay (in seconds)
69
// @Units: s
70
// @Range: 0 2
71
// @Increment: 0.1
72
// @User: Advanced
73
AP_GROUPINFO("BRK_DELAY", 6, AC_Loiter, _brake_delay, LOITER_BRAKE_START_DELAY_DEFAULT),
74
75
AP_GROUPEND
76
};
77
78
// Default constructor.
79
// Note that the Vector/Matrix constructors already implicitly zero
80
// their values.
81
//
82
AC_Loiter::AC_Loiter(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control, const AC_AttitudeControl& attitude_control) :
83
_inav(inav),
84
_ahrs(ahrs),
85
_pos_control(pos_control),
86
_attitude_control(attitude_control)
87
{
88
AP_Param::setup_object_defaults(this, var_info);
89
}
90
91
/// init_target to a position in cm from ekf origin
92
void AC_Loiter::init_target(const Vector2f& position)
93
{
94
sanity_check_params();
95
96
// initialise position controller speed and acceleration
97
_pos_control.set_correction_speed_accel_xy(LOITER_VEL_CORRECTION_MAX, _accel_cmss);
98
_pos_control.set_pos_error_max_xy_cm(LOITER_POS_CORRECTION_MAX);
99
100
// initialise position controller
101
_pos_control.init_xy_controller_stopping_point();
102
103
// initialise desired acceleration and angles to zero to remain on station
104
_predicted_accel.zero();
105
_desired_accel.zero();
106
_predicted_euler_angle.zero();
107
_brake_accel = 0.0f;
108
109
// set target position
110
_pos_control.set_pos_desired_xy_cm(position);
111
}
112
113
/// initialize's position and feed-forward velocity from current pos and velocity
114
void AC_Loiter::init_target()
115
{
116
sanity_check_params();
117
118
// initialise position controller speed and acceleration
119
_pos_control.set_correction_speed_accel_xy(LOITER_VEL_CORRECTION_MAX, _accel_cmss);
120
_pos_control.set_pos_error_max_xy_cm(LOITER_POS_CORRECTION_MAX);
121
122
// initialise position controller and move target accelerations smoothly towards zero
123
_pos_control.relax_velocity_controller_xy();
124
125
// initialise predicted acceleration and angles from the position controller
126
_predicted_accel = _pos_control.get_accel_target_cmss().xy();
127
_predicted_euler_angle.x = radians(_pos_control.get_roll_cd()*0.01f);
128
_predicted_euler_angle.y = radians(_pos_control.get_pitch_cd()*0.01f);
129
_brake_accel = 0.0f;
130
}
131
132
/// reduce response for landing
133
void AC_Loiter::soften_for_landing()
134
{
135
_pos_control.soften_for_landing_xy();
136
}
137
138
/// set pilot desired acceleration in centi-degrees
139
// dt should be the time (in seconds) since the last call to this function
140
void AC_Loiter::set_pilot_desired_acceleration(float euler_roll_angle_cd, float euler_pitch_angle_cd)
141
{
142
const float dt = _attitude_control.get_dt();
143
// Convert from centidegrees on public interface to radians
144
const float euler_roll_angle = radians(euler_roll_angle_cd * 0.01f);
145
const float euler_pitch_angle = radians(euler_pitch_angle_cd * 0.01f);
146
147
// convert our desired attitude to an acceleration vector assuming we are not accelerating vertically
148
const Vector3f desired_euler {euler_roll_angle, euler_pitch_angle, _ahrs.yaw};
149
const Vector3f desired_accel = _pos_control.lean_angles_to_accel(desired_euler);
150
151
_desired_accel.x = desired_accel.x;
152
_desired_accel.y = desired_accel.y;
153
154
// difference between where we think we should be and where we want to be
155
Vector2f angle_error(wrap_PI(euler_roll_angle - _predicted_euler_angle.x), wrap_PI(euler_pitch_angle - _predicted_euler_angle.y));
156
157
// calculate the angular velocity that we would expect given our desired and predicted attitude
158
_attitude_control.input_shaping_rate_predictor(angle_error, _predicted_euler_rate, dt);
159
160
// update our predicted attitude based on our predicted angular velocity
161
_predicted_euler_angle += _predicted_euler_rate * dt;
162
163
// convert our predicted attitude to an acceleration vector assuming we are not accelerating vertically
164
const Vector3f predicted_euler {_predicted_euler_angle.x, _predicted_euler_angle.y, _ahrs.yaw};
165
const Vector3f predicted_accel = _pos_control.lean_angles_to_accel(predicted_euler);
166
167
_predicted_accel.x = predicted_accel.x;
168
_predicted_accel.y = predicted_accel.y;
169
}
170
171
/// get vector to stopping point based on a horizontal position and velocity
172
void AC_Loiter::get_stopping_point_xy(Vector2f& stopping_point) const
173
{
174
Vector2p stop;
175
_pos_control.get_stopping_point_xy_cm(stop);
176
stopping_point = stop.tofloat();
177
}
178
179
/// get maximum lean angle when using loiter
180
float AC_Loiter::get_angle_max_cd() const
181
{
182
if (!is_positive(_angle_max)) {
183
return MIN(_attitude_control.lean_angle_max_cd(), _pos_control.get_lean_angle_max_cd()) * (2.0f/3.0f);
184
}
185
return MIN(_angle_max*100.0f, _pos_control.get_lean_angle_max_cd());
186
}
187
188
/// run the loiter controller
189
void AC_Loiter::update(bool avoidance_on)
190
{
191
calc_desired_velocity(avoidance_on);
192
_pos_control.update_xy_controller();
193
}
194
195
// sanity check parameters
196
void AC_Loiter::sanity_check_params()
197
{
198
_speed_cms.set(MAX(_speed_cms, LOITER_SPEED_MIN));
199
_accel_cmss.set(MIN(_accel_cmss, GRAVITY_MSS * 100.0f * tanf(ToRad(_attitude_control.lean_angle_max_cd() * 0.01f))));
200
}
201
202
/// calc_desired_velocity - updates desired velocity (i.e. feed forward) with pilot requested acceleration and fake wind resistance
203
/// updated velocity sent directly to position controller
204
void AC_Loiter::calc_desired_velocity(bool avoidance_on)
205
{
206
float ekfGndSpdLimit, ahrsControlScaleXY;
207
AP::ahrs().getControlLimits(ekfGndSpdLimit, ahrsControlScaleXY);
208
209
const float dt = _pos_control.get_dt();
210
211
// calculate a loiter speed limit which is the minimum of the value set by the LOITER_SPEED
212
// parameter and the value set by the EKF to observe optical flow limits
213
float gnd_speed_limit_cms = MIN(_speed_cms, ekfGndSpdLimit * 100.0f);
214
gnd_speed_limit_cms = MAX(gnd_speed_limit_cms, LOITER_SPEED_MIN);
215
216
float pilot_acceleration_max = angle_to_accel(get_angle_max_cd() * 0.01) * 100;
217
218
// range check dt
219
if (is_negative(dt)) {
220
return;
221
}
222
223
// get loiters desired velocity from the position controller where it is being stored.
224
Vector2f desired_vel = _pos_control.get_vel_desired_cms().xy();
225
226
// update the desired velocity using our predicted acceleration
227
desired_vel += _predicted_accel * dt;
228
229
Vector2f loiter_accel_brake;
230
float desired_speed = desired_vel.length();
231
if (!is_zero(desired_speed)) {
232
Vector2f desired_vel_norm = desired_vel / desired_speed;
233
234
// calculate a drag acceleration based on the desired speed.
235
float drag_decel = pilot_acceleration_max * desired_speed / gnd_speed_limit_cms;
236
237
// calculate a braking acceleration if sticks are at zero
238
float loiter_brake_accel = 0.0f;
239
if (_desired_accel.is_zero()) {
240
if ((AP_HAL::millis() - _brake_timer) > _brake_delay * 1000.0f) {
241
float brake_gain = _pos_control.get_vel_xy_pid().kP() * 0.5f;
242
loiter_brake_accel = constrain_float(sqrt_controller(desired_speed, brake_gain, _brake_jerk_max_cmsss, dt), 0.0f, _brake_accel_cmss);
243
}
244
} else {
245
loiter_brake_accel = 0.0f;
246
_brake_timer = AP_HAL::millis();
247
}
248
_brake_accel += constrain_float(loiter_brake_accel - _brake_accel, -_brake_jerk_max_cmsss * dt, _brake_jerk_max_cmsss * dt);
249
loiter_accel_brake = desired_vel_norm * _brake_accel;
250
251
// update the desired velocity using the drag and braking accelerations
252
desired_speed = MAX(desired_speed - (drag_decel + _brake_accel) * dt, 0.0f);
253
desired_vel = desired_vel_norm * desired_speed;
254
}
255
256
// add braking to the desired acceleration
257
_desired_accel -= loiter_accel_brake;
258
259
// 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)
260
float horizSpdDem = desired_vel.length();
261
if (horizSpdDem > gnd_speed_limit_cms) {
262
desired_vel = desired_vel * gnd_speed_limit_cms / horizSpdDem;
263
}
264
265
#if AP_AVOIDANCE_ENABLED && !APM_BUILD_TYPE(APM_BUILD_ArduPlane)
266
if (avoidance_on) {
267
// Limit the velocity to prevent fence violations
268
// TODO: We need to also limit the _desired_accel
269
AC_Avoid *_avoid = AP::ac_avoid();
270
if (_avoid != nullptr) {
271
Vector3f avoidance_vel_3d{desired_vel.x, desired_vel.y, 0.0f};
272
_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);
273
desired_vel = Vector2f{avoidance_vel_3d.x, avoidance_vel_3d.y};
274
}
275
}
276
#endif // !APM_BUILD_ArduPlane
277
278
// get loiters desired velocity from the position controller where it is being stored.
279
Vector2p desired_pos = _pos_control.get_pos_desired_cm().xy();
280
281
// update the desired position using our desired velocity and acceleration
282
desired_pos += (desired_vel * dt).topostype();
283
284
// send adjusted feed forward acceleration and velocity back to the Position Controller
285
_pos_control.set_pos_vel_accel_xy(desired_pos, desired_vel, _desired_accel);
286
}
287
288