Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AC_AttitudeControl/AC_PosControl.cpp
9390 views
1
#include <AP_HAL/AP_HAL.h>
2
#include "AC_PosControl.h"
3
#include <AP_Math/AP_Math.h>
4
#include <AP_Logger/AP_Logger.h>
5
#include <AP_Motors/AP_Motors.h> // motors library
6
#include <AP_Vehicle/AP_Vehicle_Type.h>
7
#include <AP_Scheduler/AP_Scheduler.h>
8
9
extern const AP_HAL::HAL& hal;
10
11
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
12
// default gains for Plane
13
# define POSCONTROL_D_POS_P 1.0f // vertical position controller P gain default
14
# define POSCONTROL_D_VEL_P 5.0f // vertical velocity controller P gain default
15
# define POSCONTROL_D_VEL_IMAX 10.0f // vertical velocity controller IMAX gain default
16
# define POSCONTROL_D_VEL_FILT_HZ 5.0f // vertical velocity controller input filter
17
# define POSCONTROL_D_VEL_FILT_D_HZ 5.0f // vertical velocity controller input filter for D
18
# define POSCONTROL_D_ACC_P 0.03f // vertical acceleration controller P gain default
19
# define POSCONTROL_D_ACC_I 0.1f // vertical acceleration controller I gain default
20
# define POSCONTROL_D_ACC_D 0.0f // vertical acceleration controller D gain default
21
# define POSCONTROL_D_ACC_IMAX 0.8f // vertical acceleration controller IMAX gain default
22
# define POSCONTROL_D_ACC_FILT_HZ 10.0f // vertical acceleration controller input filter default
23
# define POSCONTROL_D_ACC_DT 0.02f // vertical acceleration controller dt default
24
# define POSCONTROL_NE_POS_P 0.5f // horizontal position controller P gain default
25
# define POSCONTROL_NE_VEL_P 0.7f // horizontal velocity controller P gain default
26
# define POSCONTROL_NE_VEL_I 0.35f // horizontal velocity controller I gain default
27
# define POSCONTROL_NE_VEL_D 0.17f // horizontal velocity controller D gain default
28
# define POSCONTROL_NE_VEL_IMAX 10.0f // horizontal velocity controller IMAX gain default
29
# define POSCONTROL_NE_VEL_FILT_HZ 5.0f // horizontal velocity controller input filter
30
# define POSCONTROL_NE_VEL_FILT_D_HZ 5.0f // horizontal velocity controller input filter for D
31
#elif APM_BUILD_TYPE(APM_BUILD_ArduSub)
32
// default gains for Sub
33
# define POSCONTROL_D_POS_P 3.0f // vertical position controller P gain default
34
# define POSCONTROL_D_VEL_P 8.0f // vertical velocity controller P gain default
35
# define POSCONTROL_D_VEL_IMAX 10.0f // vertical velocity controller IMAX gain default
36
# define POSCONTROL_D_VEL_FILT_HZ 5.0f // vertical velocity controller input filter
37
# define POSCONTROL_D_VEL_FILT_D_HZ 5.0f // vertical velocity controller input filter for D
38
# define POSCONTROL_D_ACC_P 0.05f // vertical acceleration controller P gain default
39
# define POSCONTROL_D_ACC_I 0.01f // vertical acceleration controller I gain default
40
# define POSCONTROL_D_ACC_D 0.0f // vertical acceleration controller D gain default
41
# define POSCONTROL_D_ACC_IMAX 0.1f // vertical acceleration controller IMAX gain default
42
# define POSCONTROL_D_ACC_FILT_HZ 20.0f // vertical acceleration controller input filter default
43
# define POSCONTROL_D_ACC_DT 0.0025f // vertical acceleration controller dt default
44
# define POSCONTROL_NE_POS_P 1.0f // horizontal position controller P gain default
45
# define POSCONTROL_NE_VEL_P 1.0f // horizontal velocity controller P gain default
46
# define POSCONTROL_NE_VEL_I 0.5f // horizontal velocity controller I gain default
47
# define POSCONTROL_NE_VEL_D 0.0f // horizontal velocity controller D gain default
48
# define POSCONTROL_NE_VEL_IMAX 10.0f // horizontal velocity controller IMAX gain default
49
# define POSCONTROL_NE_VEL_FILT_HZ 5.0f // horizontal velocity controller input filter
50
# define POSCONTROL_NE_VEL_FILT_D_HZ 5.0f // horizontal velocity controller input filter for D
51
#else
52
// default gains for Copter / TradHeli
53
# define POSCONTROL_D_POS_P 1.0f // vertical position controller P gain default
54
# define POSCONTROL_D_VEL_P 5.0f // vertical velocity controller P gain default
55
# define POSCONTROL_D_VEL_IMAX 10.0f // vertical velocity controller IMAX gain default
56
# define POSCONTROL_D_VEL_FILT_HZ 5.0f // vertical velocity controller input filter
57
# define POSCONTROL_D_VEL_FILT_D_HZ 5.0f // vertical velocity controller input filter for D
58
# define POSCONTROL_D_ACC_P 0.05f // vertical acceleration controller P gain default
59
# define POSCONTROL_D_ACC_I 0.1f // vertical acceleration controller I gain default
60
# define POSCONTROL_D_ACC_D 0.0f // vertical acceleration controller D gain default
61
# define POSCONTROL_D_ACC_IMAX 0.8f // vertical acceleration controller IMAX gain default
62
# define POSCONTROL_D_ACC_FILT_HZ 20.0f // vertical acceleration controller input filter default
63
# define POSCONTROL_D_ACC_DT 0.0025f // vertical acceleration controller dt default
64
# define POSCONTROL_NE_POS_P 1.0f // horizontal position controller P gain default
65
# define POSCONTROL_NE_VEL_P 2.0f // horizontal velocity controller P gain default
66
# define POSCONTROL_NE_VEL_I 1.0f // horizontal velocity controller I gain default
67
# define POSCONTROL_NE_VEL_D 0.25f // horizontal velocity controller D gain default
68
# define POSCONTROL_NE_VEL_IMAX 10.0f // horizontal velocity controller IMAX gain default
69
# define POSCONTROL_NE_VEL_FILT_HZ 5.0f // horizontal velocity controller input filter
70
# define POSCONTROL_NE_VEL_FILT_D_HZ 5.0f // horizontal velocity controller input filter for D
71
#endif
72
73
// vibration compensation gains
74
#define POSCONTROL_VIBE_COMP_P_GAIN 0.250f
75
#define POSCONTROL_VIBE_COMP_I_GAIN 0.125f
76
77
// velocity offset targets timeout if not updated within 3 seconds
78
#define POSCONTROL_POSVELACCEL_OFFSET_TARGET_TIMEOUT_MS 3000
79
80
AC_PosControl *AC_PosControl::_singleton;
81
82
const AP_Param::GroupInfo AC_PosControl::var_info[] = {
83
// 0 was used for HOVER
84
85
// POS_ACC_XY_FILT was here.
86
87
// @Param: _D_POS_P
88
// @DisplayName: Position (vertical) controller P gain
89
// @Description: Position (vertical) controller P gain. Converts the difference between the desired altitude and actual altitude into a climb or descent rate which is passed to the throttle rate controller. Previously _POSZ_P.
90
// @Range: 0.50 4.00
91
// @Increment: 0.01
92
// @User: Standard
93
AP_SUBGROUPINFO(_p_pos_d_m, "_D_POS_", 2, AC_PosControl, AC_P_1D),
94
95
// 3 was _VELZ_ which has become _D_VEL_
96
97
// 4 was _ACCZ_ which has become _D_ACC_
98
99
// @Param: _NE_POS_P
100
// @DisplayName: Position (horizontal) controller P gain
101
// @Description: Position controller P gain. Converts the distance (in the latitude direction) to the target location into a desired speed which is then passed to the loiter latitude rate controller. Previously _POSXY_P.
102
// @Range: 0.50 4.00
103
// @Increment: 0.01
104
// @User: Standard
105
AP_SUBGROUPINFO(_p_pos_ne_m, "_NE_POS_", 5, AC_PosControl, AC_P_2D),
106
107
// 6 was _VELXY_ which has become _NE_VEL_
108
109
// @Param: _ANGLE_MAX
110
// @DisplayName: Position Control Angle Max
111
// @Description: Maximum lean angle autopilot can request. Set to zero to use ANGLE_MAX parameter value
112
// @Units: deg
113
// @Range: 0 45
114
// @Increment: 1
115
// @User: Advanced
116
AP_GROUPINFO("_ANGLE_MAX", 7, AC_PosControl, _lean_angle_max_deg, 0.0f),
117
118
// IDs 8,9 used for _TC_XY and _TC_Z in beta release candidate
119
120
// @Param: _JERK_NE
121
// @DisplayName: Jerk limit for the horizontal kinematic input shaping
122
// @Description: Jerk limit of the horizontal kinematic path generation used to determine how quickly the aircraft varies the acceleration target
123
// @Units: m/s/s/s
124
// @Range: 1 50
125
// @Increment: 1
126
// @User: Advanced
127
AP_GROUPINFO("_JERK_NE", 10, AC_PosControl, _shaping_jerk_ne_msss, POSCONTROL_JERK_NE_MSSS),
128
129
// @Param: _JERK_D
130
// @DisplayName: Jerk limit for the vertical kinematic input shaping
131
// @Description: Jerk limit of the vertical kinematic path generation used to determine how quickly the aircraft varies the acceleration target
132
// @Units: m/s/s/s
133
// @Range: 1 50
134
// @Increment: 1
135
// @User: Advanced
136
AP_GROUPINFO("_JERK_D", 11, AC_PosControl, _shaping_jerk_d_msss, POSCONTROL_JERK_D_MSSS),
137
138
// @Param: _D_VEL_P
139
// @DisplayName: Velocity (vertical) controller P gain
140
// @Description: Velocity (vertical) controller P gain. Converts the difference between desired vertical speed and actual speed into a desired acceleration that is passed to the throttle acceleration controller. Previously _VELZ_P.
141
// @Range: 1.0 10.0
142
// @Increment: 0.1
143
// @User: Standard
144
145
// @Param: _D_VEL_I
146
// @DisplayName: Velocity (vertical) controller I gain
147
// @Description: Velocity (vertical) controller I gain. Corrects long-term difference in desired velocity to a target acceleration. Previously _VELZ_I.
148
// @Range: 0.00 10.0
149
// @Increment: 0.1
150
// @User: Advanced
151
152
// @Param: _D_VEL_IMAX
153
// @DisplayName: Velocity (vertical) controller I gain maximum
154
// @Description: Velocity (vertical) controller I gain maximum. Constrains the target acceleration that the I gain will output. If upgrading from 4.6 this is _VELZ_IMAX * 0.01.
155
// @Range: 1.000 10.000
156
// @Increment: 0.1
157
// @User: Standard
158
159
// @Param: _D_VEL_D
160
// @DisplayName: Velocity (vertical) controller D gain
161
// @Description: Velocity (vertical) controller D gain. Corrects short-term changes in velocity. Previously _VELZ_D.
162
// @Range: 0.00 2.00
163
// @Increment: 0.01
164
// @User: Advanced
165
166
// @Param: _D_VEL_FF
167
// @DisplayName: Velocity (vertical) controller Feed Forward gain
168
// @Description: Velocity (vertical) controller Feed Forward gain. Produces an output that is proportional to the magnitude of the target. Previously _VELZ_FF.
169
// @Range: 0.00 2.00
170
// @Increment: 0.01
171
// @User: Advanced
172
173
// @Param: _D_VEL_FLTE
174
// @DisplayName: Velocity (vertical) error filter
175
// @Description: Velocity (vertical) error filter. This filter (in Hz) is applied to the input for P and I terms. Previously _VELZ_FLTE.
176
// @Range: 0 100
177
// @Increment: 1.0
178
// @Units: Hz
179
// @User: Advanced
180
181
// @Param: _D_VEL_FLTD
182
// @DisplayName: Velocity (vertical) input filter for D term
183
// @Description: Velocity (vertical) input filter for D term. This filter (in Hz) is applied to the input for D terms. Previously _VELZ_FLTD.
184
// @Range: 0 100
185
// @Increment: 1.0
186
// @Units: Hz
187
// @User: Advanced
188
AP_SUBGROUPINFO(_pid_vel_d_m, "_D_VEL_", 12, AC_PosControl, AC_PID_Basic),
189
190
// @Param: _D_ACC_P
191
// @DisplayName: Acceleration (vertical) controller P gain
192
// @Description: Acceleration (vertical) controller P gain. Converts the difference between desired vertical acceleration and actual acceleration into a motor output. If upgrading from 4.6 this is _ACCZ_P * 0.1.
193
// @Range: 0.010 0.250
194
// @Increment: 0.001
195
// @User: Standard
196
197
// @Param: _D_ACC_I
198
// @DisplayName: Acceleration (vertical) controller I gain
199
// @Description: Acceleration (vertical) controller I gain. Corrects long-term difference in desired vertical acceleration and actual acceleration. If upgrading from 4.6 this is _ACCZ_I * 0.1.
200
// @Range: 0.000 0.500
201
// @Increment: 0.001
202
// @User: Standard
203
204
// @Param: _D_ACC_IMAX
205
// @DisplayName: Acceleration (vertical) controller I gain maximum
206
// @Description: Acceleration (vertical) controller I gain maximum. Constrains the maximum pwm that the I term will generate. If upgrading from 4.6 this is _ACCZ_IMAX * 0.001.
207
// @Range: 0.0 1.0
208
// @Increment: 0.01
209
// @Units: d%
210
// @User: Standard
211
212
// @Param: _D_ACC_D
213
// @DisplayName: Acceleration (vertical) controller D gain
214
// @Description: Acceleration (vertical) controller D gain. Compensates for short-term change in desired vertical acceleration vs actual acceleration. If upgrading from 4.6 this is _ACCZ_D * 0.1.
215
// @Range: 0.000 0.100
216
// @Increment: 0.001
217
// @User: Standard
218
219
// @Param: _D_ACC_FF
220
// @DisplayName: Acceleration (vertical) controller feed forward
221
// @Description: Acceleration (vertical) controller feed forward. If upgrading from 4.6 this is _ACCZ_FF * 0.1.
222
// @Range: 0.000 0.100
223
// @Increment: 0.001
224
// @User: Standard
225
226
// @Param: _D_ACC_FLTT
227
// @DisplayName: Acceleration (vertical) controller target frequency in Hz
228
// @Description: Acceleration (vertical) controller target frequency in Hz. Previously _ACCZ_FLTT.
229
// @Range: 1 50
230
// @Increment: 1
231
// @Units: Hz
232
// @User: Standard
233
234
// @Param: _D_ACC_FLTE
235
// @DisplayName: Acceleration (vertical) controller error frequency in Hz
236
// @Description: Acceleration (vertical) controller error frequency in Hz. Previously _ACCZ_FLTE.
237
// @Range: 1 100
238
// @Increment: 1
239
// @Units: Hz
240
// @User: Standard
241
242
// @Param: _D_ACC_FLTD
243
// @DisplayName: Acceleration (vertical) controller derivative frequency in Hz
244
// @Description: Acceleration (vertical) controller derivative frequency in Hz. Previously _ACCZ_FLTD.
245
// @Range: 1 100
246
// @Increment: 1
247
// @Units: Hz
248
// @User: Standard
249
250
// @Param: _D_ACC_SMAX
251
// @DisplayName: Accel (vertical) slew rate limit
252
// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
253
// @Range: 0 100
254
// @Increment: 0.1
255
// @User: Advanced
256
257
// @Param: _D_ACC_PDMX
258
// @DisplayName: Acceleration (vertical) controller PD sum maximum
259
// @Description: Acceleration (vertical) controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output. If upgrading from 4.6 this is _ACCZ_P * 0.1.
260
// @Range: 0.00 1.00
261
// @Increment: 0.01
262
// @Units: d%
263
264
// @Param: _D_ACC_D_FF
265
// @DisplayName: Accel (vertical) Derivative FeedForward Gain
266
// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target. If upgrading from 4.6 this is _ACCZ_P * 0.1.
267
// @Range: 0.000 0.050
268
// @Increment: 0.001
269
// @User: Advanced
270
271
// @Param: _D_ACC_NTF
272
// @DisplayName: Accel (vertical) Target notch filter index
273
// @Description: Accel (vertical) Target notch filter index. If upgrading from 4.6 this is Previously _ACCZ_NTF.
274
// @Range: 1 8
275
// @User: Advanced
276
277
// @Param: _D_ACC_NEF
278
// @DisplayName: Accel (vertical) Error notch filter index
279
// @Description: Accel (vertical) Error notch filter index. If upgrading from 4.6 this is Previously _ACCZ_NEF.
280
// @Range: 1 8
281
// @User: Advanced
282
AP_SUBGROUPINFO(_pid_accel_d_m, "_D_ACC_", 13, AC_PosControl, AC_PID),
283
284
// @Param: _NE_VEL_P
285
// @DisplayName: Velocity (horizontal) P gain
286
// @Description: Velocity (horizontal) P gain. Converts the difference between desired and actual velocity to a target acceleration. Previously _VELXY_P.
287
// @Range: 0.10 10.00
288
// @Increment: 0.01
289
// @User: Advanced
290
291
// @Param: _NE_VEL_I
292
// @DisplayName: Velocity (horizontal) I gain
293
// @Description: Velocity (horizontal) I gain. Corrects long-term difference between desired and actual velocity to a target acceleration. Previously _VELXY_I.
294
// @Range: 0.10 10.00
295
// @Increment: 0.01
296
// @User: Advanced
297
298
// @Param: _NE_VEL_D
299
// @DisplayName: Velocity (horizontal) D gain
300
// @Description: Velocity (horizontal) D gain. Corrects short-term changes in velocity. Previously _VELXY_D.
301
// @Range: 0.00 1.00
302
// @Increment: 0.01
303
// @User: Advanced
304
305
// @Param: _NE_VEL_IMAX
306
// @DisplayName: Velocity (horizontal) integrator maximum
307
// @Description: Velocity (horizontal) integrator maximum. Constrains the target acceleration that the I gain will output. If upgrading from 4.6 this is _VELXY_IMAX * 0.01.
308
// @Range: 0 10
309
// @Increment: 1
310
// @Units: m/s/s
311
// @User: Advanced
312
313
// @Param: _NE_VEL_FLTE
314
// @DisplayName: Velocity (horizontal) input filter
315
// @Description: Velocity (horizontal) input filter. This filter (in Hz) is applied to the input for P and I terms. Previously _VELXY_FLTE.
316
// @Range: 0 100
317
// @Increment: 1
318
// @Units: Hz
319
// @User: Advanced
320
321
// @Param: _NE_VEL_FLTD
322
// @DisplayName: Velocity (horizontal) input filter
323
// @Description: Velocity (horizontal) input filter. This filter (in Hz) is applied to the input for D term. Previously _VELXY_FLTD.
324
// @Range: 0 100
325
// @Increment: 1
326
// @Units: Hz
327
// @User: Advanced
328
329
// @Param: _NE_VEL_FF
330
// @DisplayName: Velocity (horizontal) feed forward gain
331
// @Description: Velocity (horizontal) feed forward gain. Converts the difference between desired velocity to a target acceleration. Previously _VELXY_FF.
332
// @Range: 0.10 10.00
333
// @Increment: 0.01
334
// @User: Advanced
335
AP_SUBGROUPINFO(_pid_vel_ne_m, "_NE_VEL_", 14, AC_PosControl, AC_PID_2D),
336
337
AP_GROUPEND
338
};
339
340
// Default constructor.
341
// Note that the Vector/Matrix constructors already implicitly zero
342
// their values.
343
//
344
AC_PosControl::AC_PosControl(AP_AHRS_View& ahrs, const AP_Motors& motors, AC_AttitudeControl& attitude_control) :
345
_ahrs(ahrs),
346
_motors(motors),
347
_attitude_control(attitude_control),
348
_p_pos_ne_m(POSCONTROL_NE_POS_P),
349
_p_pos_d_m(POSCONTROL_D_POS_P),
350
_pid_vel_ne_m(POSCONTROL_NE_VEL_P, POSCONTROL_NE_VEL_I, POSCONTROL_NE_VEL_D, 0.0f, POSCONTROL_NE_VEL_IMAX, POSCONTROL_NE_VEL_FILT_HZ, POSCONTROL_NE_VEL_FILT_D_HZ),
351
_pid_vel_d_m(POSCONTROL_D_VEL_P, 0.0f, 0.0f, 0.0f, POSCONTROL_D_VEL_IMAX, POSCONTROL_D_VEL_FILT_HZ, POSCONTROL_D_VEL_FILT_D_HZ),
352
_pid_accel_d_m(POSCONTROL_D_ACC_P, POSCONTROL_D_ACC_I, POSCONTROL_D_ACC_D, 0.0f, POSCONTROL_D_ACC_IMAX, 0.0f, POSCONTROL_D_ACC_FILT_HZ, 0.0f),
353
_vel_max_ne_ms(POSCONTROL_SPEED_MS),
354
_vel_max_up_ms(POSCONTROL_SPEED_UP_MS),
355
_vel_max_down_ms(POSCONTROL_SPEED_DOWN_MS),
356
_accel_max_ne_mss(POSCONTROL_ACCEL_NE_MSS),
357
_accel_max_d_mss(POSCONTROL_ACCEL_D_MSS),
358
_jerk_max_ne_msss(POSCONTROL_JERK_NE_MSSS),
359
_jerk_max_d_msss(POSCONTROL_JERK_D_MSSS)
360
{
361
AP_Param::setup_object_defaults(this, var_info);
362
363
_singleton = this;
364
}
365
366
367
///
368
/// 3D position shaper
369
///
370
371
// Sets a new NED position target in meters and computes a jerk-limited trajectory.
372
// Updates internal acceleration commands using a smooth kinematic path constrained
373
// by configured acceleration and jerk limits.
374
// The path can be offset vertically to follow the terrain by providing the current
375
// terrain level in the NED frame and the terrain margin. Terrain margin is used to
376
// constrain horizontal velocity to avoid vertical buffer violation.
377
void AC_PosControl::input_pos_NED_m(const Vector3p& pos_ned_m, float pos_terrain_target_d_m, float terrain_margin_m)
378
{
379
// Terrain following velocity scalar must be calculated before we remove the position offset
380
const float offset_d_scalar = terrain_scaler_D_m(pos_terrain_target_d_m, terrain_margin_m);
381
set_pos_terrain_target_D_m(pos_terrain_target_d_m);
382
383
// calculated increased maximum acceleration and jerk if over speed
384
const float overspeed_gain = calculate_overspeed_gain();
385
const float accel_max_d_mss = _accel_max_d_mss * overspeed_gain;
386
const float jerk_max_d_msss = _jerk_max_d_msss * overspeed_gain;
387
388
update_pos_vel_accel_xy(_pos_desired_ned_m.xy(), _vel_desired_ned_ms.xy(), _accel_desired_ned_mss.xy(), _dt_s, _limit_vector_ned.xy(), _p_pos_ne_m.get_error(), _pid_vel_ne_m.get_error());
389
390
// adjust desired altitude if motors have not hit their limits
391
update_pos_vel_accel(_pos_desired_ned_m.z, _vel_desired_ned_ms.z, _accel_desired_ned_mss.z, _dt_s, _limit_vector_ned.z, _p_pos_d_m.get_error(), _pid_vel_d_m.get_error());
392
393
// calculate the horizontal and vertical velocity limits to travel directly to the destination defined by pos_ne_m
394
float vel_max_ne_ms = 0.0f;
395
float vel_max_d_ms = 0.0f;
396
Vector3f travel_dir_unit = (pos_ned_m - _pos_desired_ned_m).tofloat();
397
if (is_positive(travel_dir_unit.length_squared()) ) {
398
travel_dir_unit.normalize();
399
float travel_dir_unit_ne_length = travel_dir_unit.xy().length();
400
401
float vel_max_ms = kinematic_limit(travel_dir_unit, _vel_max_ne_ms, _vel_max_up_ms, _vel_max_down_ms);
402
vel_max_ne_ms = vel_max_ms * travel_dir_unit_ne_length;
403
vel_max_d_ms = fabsf(vel_max_ms * travel_dir_unit.z);
404
}
405
406
// reduce speed if we are reaching the edge of our vertical buffer
407
vel_max_ne_ms *= offset_d_scalar;
408
409
Vector2f vel_ne_ms;
410
Vector2f accel_ne_mss;
411
shape_pos_vel_accel_xy(pos_ned_m.xy(), vel_ne_ms, accel_ne_mss, _pos_desired_ned_m.xy(), _vel_desired_ned_ms.xy(), _accel_desired_ned_mss.xy(),
412
vel_max_ne_ms, _accel_max_ne_mss, _jerk_max_ne_msss, _dt_s, false);
413
414
float pos_d_m = pos_ned_m.z;
415
shape_pos_vel_accel(pos_d_m, 0, 0,
416
_pos_desired_ned_m.z, _vel_desired_ned_ms.z, _accel_desired_ned_mss.z,
417
-vel_max_d_ms, vel_max_d_ms,
418
-accel_max_d_mss, constrain_float(accel_max_d_mss, 0.0, 7.5),
419
jerk_max_d_msss, _dt_s, false);
420
}
421
422
// Returns a scaling factor for horizontal velocity in m/s to ensure
423
// the vertical controller maintains a safe distance above terrain.
424
float AC_PosControl::terrain_scaler_D_m(float pos_terrain_d_m, float terrain_margin_m) const
425
{
426
if (is_zero(terrain_margin_m)) {
427
return 1.0;
428
}
429
float pos_offset_error_d_m = _pos_estimate_ned_m.z - (_pos_target_ned_m.z + (pos_terrain_d_m - _pos_terrain_d_m));
430
return constrain_float((1.0 - (fabsf(pos_offset_error_d_m) - 0.5 * terrain_margin_m) / (0.5 * terrain_margin_m)), 0.01, 1.0);
431
}
432
433
///
434
/// Lateral position controller
435
///
436
437
// Sets maximum horizontal speed (cm/s) and acceleration (cm/s²) for NE-axis shaping.
438
// Can be called anytime; transitions are handled smoothly.
439
// All arguments should be positive.
440
// See NE_set_max_speed_accel_m() for full details.
441
void AC_PosControl::NE_set_max_speed_accel_cm(float speed_ne_cms, float accel_ne_cmss)
442
{
443
NE_set_max_speed_accel_m(speed_ne_cms * 0.01, accel_ne_cmss * 0.01);
444
}
445
446
// Sets maximum horizontal speed (m/s) and acceleration (m/s²) for NE-axis shaping.
447
// These values constrain the kinematic trajectory used by the lateral controller.
448
// All arguments should be positive.
449
void AC_PosControl::NE_set_max_speed_accel_m(float speed_ne_ms, float accel_ne_mss)
450
{
451
_vel_max_ne_ms = fabsf(speed_ne_ms);
452
_accel_max_ne_mss = fabsf(accel_ne_mss);
453
454
// ensure the horizontal jerk is less than the vehicle is capable of
455
const float jerk_max_msss = MIN(_attitude_control.get_ang_vel_roll_max_rads(), _attitude_control.get_ang_vel_pitch_max_rads()) * GRAVITY_MSS;
456
const float snap_max_mssss = MIN(_attitude_control.get_accel_roll_max_radss(), _attitude_control.get_accel_pitch_max_radss()) * GRAVITY_MSS;
457
458
// get specified jerk limit
459
_jerk_max_ne_msss = _shaping_jerk_ne_msss;
460
461
// limit maximum jerk based on maximum angular rate
462
if (is_positive(jerk_max_msss) && _attitude_control.get_bf_feedforward()) {
463
_jerk_max_ne_msss = MIN(_jerk_max_ne_msss, jerk_max_msss);
464
}
465
466
// limit maximum jerk to maximum possible average jerk based on angular acceleration
467
if (is_positive(snap_max_mssss) && _attitude_control.get_bf_feedforward()) {
468
_jerk_max_ne_msss = MIN(0.5 * safe_sqrt(_accel_max_ne_mss * snap_max_mssss), _jerk_max_ne_msss);
469
}
470
}
471
472
// Sets horizontal correction limits for velocity (cm/s) and acceleration (cm/s²).
473
// Should be called only during initialization to avoid control discontinuities.
474
// All arguments should be positive.
475
// See NE_set_correction_speed_accel_m() for full details.
476
void AC_PosControl::NE_set_correction_speed_accel_cm(float speed_ne_cms, float accel_ne_cmss)
477
{
478
NE_set_correction_speed_accel_m(speed_ne_cms * 0.01, accel_ne_cmss * 0.01);
479
}
480
481
// Sets horizontal correction limits for velocity (m/s) and acceleration (m/s²).
482
// These values constrain the PID correction path, not the desired trajectory.
483
// All arguments should be positive.
484
void AC_PosControl::NE_set_correction_speed_accel_m(float speed_ne_ms, float accel_ne_mss)
485
{
486
// limits that are not positive are ignored
487
_p_pos_ne_m.set_limits(speed_ne_ms, accel_ne_mss, 0.0f);
488
}
489
490
// Initializes NE controller to a stationary stopping point with zero velocity and acceleration.
491
// Use when the expected trajectory begins at rest but the starting position is unspecified.
492
// The starting position can be retrieved with get_pos_target_NED_m().
493
void AC_PosControl::NE_init_controller_stopping_point()
494
{
495
NE_init_controller();
496
497
get_stopping_point_NE_m(_pos_desired_ned_m.xy());
498
_pos_target_ned_m.xy() = _pos_desired_ned_m.xy() + _pos_offset_ned_m.xy();
499
_vel_desired_ned_ms.xy().zero();
500
_accel_desired_ned_mss.xy().zero();
501
}
502
503
// Smoothly decays NE acceleration over time to zero while maintaining current velocity and position.
504
// Reduces output acceleration by ~95% over 0.5 seconds to avoid abrupt transitions.
505
void AC_PosControl::NE_relax_velocity_controller()
506
{
507
// decay acceleration and therefore current attitude target to zero
508
// this will be reset by NE_init_controller() if !NE_is_active()
509
if (is_positive(_dt_s)) {
510
float decay = 1.0 - _dt_s / (_dt_s + POSCONTROL_RELAX_TC);
511
_accel_target_ned_mss.xy() *= decay;
512
}
513
514
NE_init_controller();
515
}
516
517
// Softens NE controller for landing by reducing position error and suppressing I-term windup.
518
// Used to make descent behavior more stable near ground contact.
519
void AC_PosControl::NE_soften_for_landing()
520
{
521
// decay position error to zero
522
if (is_positive(_dt_s)) {
523
_pos_target_ned_m.xy() += (_pos_estimate_ned_m.xy() - _pos_target_ned_m.xy()) * (_dt_s / (_dt_s + POSCONTROL_RELAX_TC));
524
_pos_desired_ned_m.xy() = _pos_target_ned_m.xy() - _pos_offset_ned_m.xy();
525
}
526
527
// Prevent I term build up in xy velocity controller.
528
// Note that this flag is reset on each loop in NE_update_controller()
529
NE_set_externally_limited();
530
}
531
532
// Fully initializes the NE controller with current position, velocity, acceleration, and attitude.
533
// Intended for normal startup when the full state is known.
534
// Private function shared by other NE initializers.
535
void AC_PosControl::NE_init_controller()
536
{
537
// initialise offsets to target offsets and ensure offset targets are zero if they have not been updated.
538
NE_init_offsets();
539
540
// set roll, pitch lean angle targets to current attitude
541
const Vector3f &att_target_euler_rad = _attitude_control.get_att_target_euler_rad();
542
_roll_target_rad = att_target_euler_rad.x;
543
_pitch_target_rad = att_target_euler_rad.y;
544
_yaw_target_rad = att_target_euler_rad.z; // todo: this should be thrust vector heading, not yaw.
545
_yaw_rate_target_rads = 0.0f;
546
_angle_max_override_rad = 0.0;
547
548
_pos_target_ned_m.xy() = _pos_estimate_ned_m.xy();
549
_pos_desired_ned_m.xy() = _pos_target_ned_m.xy() - _pos_offset_ned_m.xy();
550
551
_vel_target_ned_ms.xy() = _vel_estimate_ned_ms.xy();
552
_vel_desired_ned_ms.xy() = _vel_target_ned_ms.xy() - _vel_offset_ned_ms.xy();
553
554
// Set desired acceleration to zero because raw acceleration is prone to noise
555
_accel_desired_ned_mss.xy().zero();
556
557
if (!NE_is_active()) {
558
lean_angles_to_accel_NE_mss(_accel_target_ned_mss.x, _accel_target_ned_mss.y);
559
}
560
561
// limit acceleration using maximum lean angles
562
const float angle_max_rad = MIN(_attitude_control.get_althold_lean_angle_max_rad(), get_lean_angle_max_rad());
563
const float accel_max_mss = angle_rad_to_accel_mss(angle_max_rad);
564
_accel_target_ned_mss.xy().limit_length(accel_max_mss);
565
566
// initialise I terms from lean angles
567
_pid_vel_ne_m.reset_filter();
568
// initialise the I term to (_accel_target_ned_mss - _accel_desired_ned_mss)
569
// _accel_desired_ned_mss is zero and can be removed from the equation
570
_pid_vel_ne_m.set_integrator((_accel_target_ned_mss.xy() - _vel_target_ned_ms.xy() * _pid_vel_ne_m.ff()));
571
572
// initialise ekf xy reset handler
573
NE_init_ekf_reset();
574
575
// initialise z_controller time out
576
_last_update_ne_ticks = AP::scheduler().ticks32();
577
}
578
579
// Sets the desired NE-plane acceleration in m/s² using jerk-limited shaping.
580
// Smoothly transitions to the specified acceleration from current kinematic state.
581
// Constraints: max acceleration and jerk set via NE_set_max_speed_accel_m().
582
void AC_PosControl::input_accel_NE_m(const Vector2f& accel_ne_mss)
583
{
584
update_pos_vel_accel_xy(_pos_desired_ned_m.xy(), _vel_desired_ned_ms.xy(), _accel_desired_ned_mss.xy(), _dt_s, _limit_vector_ned.xy(), _p_pos_ne_m.get_error(), _pid_vel_ne_m.get_error());
585
shape_accel_xy(accel_ne_mss, _accel_desired_ned_mss.xy(), _jerk_max_ne_msss, _dt_s);
586
}
587
588
// Sets desired NE-plane velocity and acceleration (cm/s, cm/s²) using jerk-limited shaping.
589
// See input_vel_accel_NE_m() for full details.
590
void AC_PosControl::input_vel_accel_NE_cm(Vector2f& vel_ne_cms, const Vector2f& accel_ne_cmss, bool limit_output)
591
{
592
Vector2f vel_ne_ms = vel_ne_cms * 0.01;
593
input_vel_accel_NE_m(vel_ne_ms, accel_ne_cmss * 0.01, limit_output);
594
vel_ne_cms = vel_ne_ms * 100.0;
595
}
596
597
// Sets desired NE-plane velocity and acceleration (m/s, m/s²) using jerk-limited shaping.
598
// Calculates target acceleration using current kinematics constrained by acceleration and jerk limits.
599
// If `limit_output` is true, applies limits to total command (desired + correction).
600
void AC_PosControl::input_vel_accel_NE_m(Vector2f& vel_ne_ms, const Vector2f& accel_ne_mss, bool limit_output)
601
{
602
update_pos_vel_accel_xy(_pos_desired_ned_m.xy(), _vel_desired_ned_ms.xy(), _accel_desired_ned_mss.xy(), _dt_s, _limit_vector_ned.xy(), _p_pos_ne_m.get_error(), _pid_vel_ne_m.get_error());
603
604
shape_vel_accel_xy(vel_ne_ms, accel_ne_mss, _vel_desired_ned_ms.xy(), _accel_desired_ned_mss.xy(),
605
_accel_max_ne_mss, _jerk_max_ne_msss, _dt_s, limit_output);
606
607
update_vel_accel_xy(vel_ne_ms, accel_ne_mss, _dt_s, Vector2f(), Vector2f());
608
}
609
610
// Sets desired NE position, velocity, and acceleration (cm, cm/s, cm/s²) with jerk-limited shaping.
611
// See input_pos_vel_accel_NE_m() for full details.
612
void AC_PosControl::input_pos_vel_accel_NE_cm(Vector2p& pos_ne_cm, Vector2f& vel_ne_cms, const Vector2f& accel_ne_cmss, bool limit_output)
613
{
614
Vector2p pos_ne_m = pos_ne_cm * 0.01;
615
Vector2f vel_ne_ms = vel_ne_cms * 0.01;
616
input_pos_vel_accel_NE_m(pos_ne_m, vel_ne_ms, accel_ne_cmss * 0.01, limit_output);
617
pos_ne_cm = pos_ne_m * 100.0;
618
vel_ne_cms = vel_ne_ms * 100.0;
619
}
620
621
// Sets desired NE position, velocity, and acceleration (m, m/s, m/s²) with jerk-limited shaping.
622
// Calculates acceleration trajectory based on current kinematics and constraints.
623
// If `limit_output` is true, limits apply to full command (desired + correction).
624
void AC_PosControl::input_pos_vel_accel_NE_m(Vector2p& pos_ne_m, Vector2f& vel_ne_ms, const Vector2f& accel_ne_mss, bool limit_output)
625
{
626
update_pos_vel_accel_xy(_pos_desired_ned_m.xy(), _vel_desired_ned_ms.xy(), _accel_desired_ned_mss.xy(), _dt_s, _limit_vector_ned.xy(), _p_pos_ne_m.get_error(), _pid_vel_ne_m.get_error());
627
628
shape_pos_vel_accel_xy(pos_ne_m, vel_ne_ms, accel_ne_mss, _pos_desired_ned_m.xy(), _vel_desired_ned_ms.xy(), _accel_desired_ned_mss.xy(),
629
_vel_max_ne_ms, _accel_max_ne_mss, _jerk_max_ne_msss, _dt_s, limit_output);
630
631
update_pos_vel_accel_xy(pos_ne_m, vel_ne_ms, accel_ne_mss, _dt_s, Vector2f(), Vector2f(), Vector2f());
632
}
633
634
// Updates NE offsets by gradually moving them toward their targets.
635
void AC_PosControl::NE_update_offsets()
636
{
637
// Check if NE offset targets have timed out
638
uint32_t now_ms = AP_HAL::millis();
639
if (now_ms - _posvelaccel_offset_target_ne_ms > POSCONTROL_POSVELACCEL_OFFSET_TARGET_TIMEOUT_MS) {
640
// Timeout: reset all NE offset targets to zero
641
_pos_offset_target_ned_m.xy().zero();
642
_vel_offset_target_ned_ms.xy().zero();
643
_accel_offset_target_ned_mss.xy().zero();
644
}
645
646
// Advance offset target kinematic state (position, velocity, accel)
647
update_pos_vel_accel_xy(_pos_offset_target_ned_m.xy(), _vel_offset_target_ned_ms.xy(), _accel_offset_target_ned_mss.xy(), _dt_s, Vector2f(), Vector2f(), Vector2f());
648
update_pos_vel_accel_xy(_pos_offset_ned_m.xy(), _vel_offset_ned_ms.xy(), _accel_offset_ned_mss.xy(), _dt_s, _limit_vector_ned.xy(), _p_pos_ne_m.get_error(), _pid_vel_ne_m.get_error());
649
650
// Shape the offset path from current to target using jerk-limited smoothing
651
shape_pos_vel_accel_xy(_pos_offset_target_ned_m.xy(), _vel_offset_target_ned_ms.xy(), _accel_offset_target_ned_mss.xy(),
652
_pos_offset_ned_m.xy(), _vel_offset_ned_ms.xy(), _accel_offset_ned_mss.xy(),
653
_vel_max_ne_ms, _accel_max_ne_mss, _jerk_max_ne_msss, _dt_s, false);
654
}
655
656
// Disables NE position correction by setting the target position to the current position.
657
// Useful to freeze positional control without disrupting velocity control.
658
void AC_PosControl::NE_stop_pos_stabilisation()
659
{
660
_pos_target_ned_m.xy() = _pos_estimate_ned_m.xy();
661
_pos_desired_ned_m.xy() = _pos_target_ned_m.xy() - _pos_offset_ned_m.xy();
662
}
663
664
// Disables NE position and velocity correction by setting target values to current state.
665
// Useful to prevent further corrections and freeze motion stabilization in NE axes.
666
void AC_PosControl::NE_stop_vel_stabilisation()
667
{
668
_pos_target_ned_m.xy() = _pos_estimate_ned_m.xy();
669
_pos_desired_ned_m.xy() = _pos_target_ned_m.xy() - _pos_offset_ned_m.xy();
670
671
_vel_target_ned_ms.xy() = _vel_estimate_ned_ms.xy();
672
_vel_desired_ned_ms.xy() = _vel_target_ned_ms.xy() - _vel_offset_ned_ms.xy();
673
674
// reset I terms
675
_pid_vel_ne_m.reset_filter();
676
_pid_vel_ne_m.reset_I();
677
}
678
679
// Returns true if the NE position controller has run in the last 5 control loop cycles.
680
bool AC_PosControl::NE_is_active() const
681
{
682
const uint32_t dt_ticks = AP::scheduler().ticks32() - _last_update_ne_ticks;
683
return dt_ticks <= 1;
684
}
685
686
// Uses P and PID controllers to generate corrections which are added to feedforward velocity/acceleration.
687
// Requires all desired targets to be pre-set using the input_* or set_* methods.
688
void AC_PosControl::NE_update_controller()
689
{
690
// check for ekf xy position reset
691
NE_handle_ekf_reset();
692
693
// Check for position control time out
694
if (!NE_is_active()) {
695
NE_init_controller();
696
if (has_good_timing()) {
697
// call internal error because initialisation has not been done
698
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
699
}
700
}
701
_last_update_ne_ticks = AP::scheduler().ticks32();
702
703
float ahrsGndSpdLimit, ahrsControlScaleXY;
704
AP::ahrs().getControlLimits(ahrsGndSpdLimit, ahrsControlScaleXY);
705
706
// Update lateral position, velocity, and acceleration offsets using path shaping
707
NE_update_offsets();
708
709
// Position Controller
710
711
// Combine position target with active NE offset to get absolute target
712
_pos_target_ned_m.xy() = _pos_desired_ned_m.xy() + _pos_offset_ned_m.xy();
713
714
// determine the combined position of the actual position and the disturbance from system ID mode
715
// calculate the target velocity correction
716
Vector2p comb_pos_ne_m = _pos_estimate_ned_m.xy();
717
comb_pos_ne_m += _disturb_pos_ne_m.topostype();
718
719
// Run P controller to compute velocity setpoint from position error
720
Vector2f vel_target_ne_ms = _p_pos_ne_m.update_all(_pos_target_ned_m.xy(), comb_pos_ne_m);
721
_pos_desired_ned_m.xy() = _pos_target_ned_m.xy() - _pos_offset_ned_m.xy();
722
723
// Velocity Controller
724
725
// Apply AHRS scaling (e.g. for optical flow noise compensation)
726
vel_target_ne_ms *= ahrsControlScaleXY;
727
vel_target_ne_ms *= _ne_control_scale_factor;
728
729
_vel_target_ned_ms.xy() = vel_target_ne_ms;
730
_vel_target_ned_ms.xy() += _vel_desired_ned_ms.xy() + _vel_offset_ned_ms.xy();
731
732
// Velocity Controller
733
734
// determine the combined velocity of the actual velocity and the disturbance from system ID mode
735
Vector2f comb_vel_ne_ms = _vel_estimate_ned_ms.xy();
736
comb_vel_ne_ms += _disturb_vel_ne_ms;
737
738
// Run velocity PID controller and scale result for control authority
739
Vector2f accel_target_ne_mss = _pid_vel_ne_m.update_all(_vel_target_ned_ms.xy(), comb_vel_ne_ms, _dt_s, _limit_vector_ned.xy());
740
741
// Acceleration Controller
742
743
// Apply AHRS scaling again to correct for measurement distortions
744
accel_target_ne_mss *= ahrsControlScaleXY;
745
accel_target_ne_mss *= _ne_control_scale_factor;
746
747
_ne_control_scale_factor = 1.0;
748
749
// pass the correction acceleration to the target acceleration output
750
_accel_target_ned_mss.xy() = accel_target_ne_mss;
751
_accel_target_ned_mss.xy() += _accel_desired_ned_mss.xy() + _accel_offset_ned_mss.xy();
752
753
// limit acceleration using maximum lean angles
754
const float angle_max_rad = MIN(_attitude_control.get_althold_lean_angle_max_rad(), get_lean_angle_max_rad());
755
const float accel_max_mss = angle_rad_to_accel_mss(angle_max_rad);
756
// Save unbounded target for use in "limited" check (not unit-consistent with z!)
757
_limit_vector_ned.xy() = _accel_target_ned_mss.xy();
758
if (!limit_accel_xy(_vel_desired_ned_ms.xy(), _accel_target_ned_mss.xy(), accel_max_mss)) {
759
// _accel_target_ned_mss was not limited so we can zero the xy limit vector
760
_limit_vector_ned.xy().zero();
761
}
762
763
// Convert acceleration to roll/pitch angle targets (used by attitude controller)
764
accel_NE_mss_to_lean_angles_rad(_accel_target_ned_mss.x, _accel_target_ned_mss.y, _roll_target_rad, _pitch_target_rad);
765
766
// Update yaw and yaw rate targets to match heading of motion
767
calculate_yaw_and_rate_yaw();
768
769
// reset the disturbance from system ID mode to zero
770
_disturb_pos_ne_m.zero();
771
_disturb_vel_ne_ms.zero();
772
}
773
774
775
///
776
/// Vertical position controller
777
///
778
779
// Sets maximum climb/descent rate (cm/s) and vertical acceleration (cm/s²) for the U-axis.
780
// See D_set_max_speed_accel_m() for full details.
781
// All values must be positive.
782
void AC_PosControl::D_set_max_speed_accel_cm(float decent_speed_max_cms, float climb_speed_max_cms, float accel_max_u_cmss)
783
{
784
D_set_max_speed_accel_m(decent_speed_max_cms * 0.01, climb_speed_max_cms * 0.01, accel_max_u_cmss * 0.01);
785
}
786
787
// Sets maximum climb/descent rate (m/s) and vertical acceleration (m/s²) for the U-axis.
788
// These values are used for jerk-limited kinematic shaping of the vertical trajectory.
789
// All values must be positive.
790
void AC_PosControl::D_set_max_speed_accel_m(float decent_speed_max_ms, float climb_speed_max_ms, float accel_max_d_mss)
791
{
792
// sanity check and update
793
if (!is_zero(decent_speed_max_ms)) {
794
_vel_max_down_ms = fabsf(decent_speed_max_ms);
795
}
796
if (!is_zero(climb_speed_max_ms)) {
797
_vel_max_up_ms = fabsf(climb_speed_max_ms);
798
}
799
if (!is_zero(accel_max_d_mss)) {
800
_accel_max_d_mss = fabsf(accel_max_d_mss);
801
}
802
803
// ensure the vertical Jerk is not limited by the filters in the Z acceleration PID object
804
_jerk_max_d_msss = _shaping_jerk_d_msss;
805
if (is_positive(_pid_accel_d_m.filt_T_hz())) {
806
_jerk_max_d_msss = MIN(_jerk_max_d_msss, MIN(GRAVITY_MSS, _accel_max_d_mss) * (M_2PI * _pid_accel_d_m.filt_T_hz()) / 5.0);
807
}
808
if (is_positive(_pid_accel_d_m.filt_E_hz())) {
809
_jerk_max_d_msss = MIN(_jerk_max_d_msss, MIN(GRAVITY_MSS, _accel_max_d_mss) * (M_2PI * _pid_accel_d_m.filt_E_hz()) / 5.0);
810
}
811
}
812
813
// Sets vertical correction velocity and acceleration limits (cm/s, cm/s²).
814
// Should only be called during initialization to avoid discontinuities.
815
// See set_correction_speed_accel_U_m() for full details.
816
// All values must be positive.
817
void AC_PosControl::D_set_correction_speed_accel_cm(float decent_speed_max_cms, float climb_speed_max_cms, float accel_max_u_cmss)
818
{
819
D_set_correction_speed_accel_m(decent_speed_max_cms * 0.01, climb_speed_max_cms * 0.01, accel_max_u_cmss * 0.01);
820
}
821
822
// Sets vertical correction velocity and acceleration limits (m/s, m/s²).
823
// These values constrain the correction output of the PID controller.
824
// All values must be positive.
825
void AC_PosControl::D_set_correction_speed_accel_m(float decent_speed_max_ms, float climb_speed_max_ms, float accel_max_d_mss)
826
{
827
// define maximum position error and maximum first and second differential limits
828
_p_pos_d_m.set_limits(-fabsf(decent_speed_max_ms), fabsf(climb_speed_max_ms), fabsf(accel_max_d_mss), 0.0f);
829
}
830
831
// Initializes U-axis controller to current position, velocity, and acceleration, disallowing descent.
832
// Used for takeoff or hold scenarios where downward motion is prohibited.
833
void AC_PosControl::D_init_controller_no_descent()
834
{
835
// Initialise the position controller to the current throttle, position, velocity and acceleration.
836
D_init_controller();
837
838
// remove all descent if present
839
_vel_target_ned_ms.z = MIN(0.0, _vel_target_ned_ms.z);
840
_vel_desired_ned_ms.z = MIN(0.0, _vel_desired_ned_ms.z);
841
_vel_terrain_d_ms = MIN(0.0, _vel_terrain_d_ms);
842
_vel_offset_ned_ms.z = MIN(0.0, _vel_offset_ned_ms.z);
843
_accel_target_ned_mss.z = MIN(0.0, _accel_target_ned_mss.z);
844
_accel_desired_ned_mss.z = MIN(0.0, _accel_desired_ned_mss.z);
845
_accel_terrain_d_mss = MIN(0.0, _accel_terrain_d_mss);
846
_accel_offset_ned_mss.z = MIN(0.0, _accel_offset_ned_mss.z);
847
}
848
849
// Initializes U-axis controller to a stationary stopping point with zero velocity and acceleration.
850
// Used when the trajectory starts at rest but the initial altitude is unspecified.
851
// The resulting position target can be retrieved with get_pos_target_NED_m().
852
void AC_PosControl::D_init_controller_stopping_point()
853
{
854
// Initialise the position controller to the current throttle, position, velocity and acceleration.
855
D_init_controller();
856
857
get_stopping_point_D_m(_pos_desired_ned_m.z);
858
_pos_target_ned_m.z = _pos_desired_ned_m.z + _pos_offset_ned_m.z;
859
_vel_desired_ned_ms.z = 0.0f;
860
_accel_desired_ned_mss.z = 0.0f;
861
}
862
863
// Smoothly decays U-axis acceleration to zero over time while maintaining current vertical velocity.
864
// Reduces requested acceleration by ~95% every 0.5 seconds to avoid abrupt transitions.
865
// `throttle_setting` is used to determine whether to preserve positive acceleration in low-thrust cases.
866
void AC_PosControl::D_relax_controller(float throttle_setting)
867
{
868
// Initialise the position controller to the current position, velocity and acceleration.
869
D_init_controller();
870
871
// D_init_controller has set the acceleration PID I term to generate the current throttle set point
872
// Use relax_integrator to decay the throttle set point to throttle_setting
873
_pid_accel_d_m.relax_integrator(-(throttle_setting - _motors.get_throttle_hover()), _dt_s, POSCONTROL_RELAX_TC);
874
}
875
876
// Fully initializes the U-axis controller with current position, velocity, acceleration, and attitude.
877
// Used during standard controller activation when full state is known.
878
// Private function shared by other vertical initializers.
879
void AC_PosControl::D_init_controller()
880
{
881
// initialise terrain targets and offsets to zero
882
init_terrain();
883
884
// initialise offsets to target offsets and ensure offset targets are zero if they have not been updated.
885
D_init_offsets();
886
887
_pos_target_ned_m.z = _pos_estimate_ned_m.z;
888
_pos_desired_ned_m.z = _pos_target_ned_m.z - _pos_offset_ned_m.z;
889
890
_vel_target_ned_ms.z = _vel_estimate_ned_ms.z;
891
_vel_desired_ned_ms.z = _vel_target_ned_ms.z - _vel_offset_ned_ms.z;
892
893
// Reset I term of velocity PID
894
_pid_vel_d_m.reset_filter();
895
_pid_vel_d_m.set_integrator(0.0f);
896
897
_accel_target_ned_mss.z = constrain_float(get_estimated_accel_D_mss(), -_accel_max_d_mss, _accel_max_d_mss);
898
_accel_desired_ned_mss.z = _accel_target_ned_mss.z - (_accel_offset_ned_mss.z + _accel_terrain_d_mss);
899
_pid_accel_d_m.reset_filter();
900
901
// Set acceleration PID I term based on the current throttle
902
// Remove the expected P term due to _accel_desired_ned_mss.z being constrained to _accel_max_d_mss
903
// Remove the expected FF term due to non-zero _accel_target_ned_mss.z
904
_pid_accel_d_m.set_integrator(-(_attitude_control.get_throttle_in() - _motors.get_throttle_hover())
905
- _pid_accel_d_m.kP() * (_accel_target_ned_mss.z - get_estimated_accel_D_mss())
906
- _pid_accel_d_m.ff() * _accel_target_ned_mss.z);
907
908
// initialise ekf z reset handler
909
D_init_ekf_reset();
910
911
// initialise z_controller time out
912
_last_update_d_ticks = AP::scheduler().ticks32();
913
}
914
915
// Sets the desired vertical acceleration in m/s² using jerk-limited shaping.
916
// Smoothly transitions to the target acceleration from current kinematic state.
917
// Constraints: max acceleration and jerk set via D_set_max_speed_accel_m().
918
void AC_PosControl::input_accel_D_m(float accel_d_mss)
919
{
920
// calculated increased maximum jerk if over speed
921
float jerk_max_d_msss = _jerk_max_d_msss * calculate_overspeed_gain();
922
923
// adjust desired alt if motors have not hit their limits
924
update_pos_vel_accel(_pos_desired_ned_m.z, _vel_desired_ned_ms.z, _accel_desired_ned_mss.z, _dt_s, _limit_vector_ned.z, _p_pos_d_m.get_error(), _pid_vel_d_m.get_error());
925
926
shape_accel(accel_d_mss, _accel_desired_ned_mss.z, jerk_max_d_msss, _dt_s);
927
}
928
929
// Sets desired vertical velocity and acceleration (m/s, m/s²) using jerk-limited shaping.
930
// Calculates required acceleration using current vertical kinematics.
931
// If `limit_output` is true, limits apply to the combined (desired + correction) command.
932
void AC_PosControl::input_vel_accel_D_m(float &vel_d_ms, float accel_d_mss, bool limit_output)
933
{
934
// calculated increased maximum acceleration and jerk if over speed
935
const float overspeed_gain = calculate_overspeed_gain();
936
const float accel_max_d_mss = _accel_max_d_mss * overspeed_gain;
937
const float jerk_max_d_msss = _jerk_max_d_msss * overspeed_gain;
938
939
// adjust desired alt if motors have not hit their limits
940
update_pos_vel_accel(_pos_desired_ned_m.z, _vel_desired_ned_ms.z, _accel_desired_ned_mss.z, _dt_s, _limit_vector_ned.z, _p_pos_d_m.get_error(), _pid_vel_d_m.get_error());
941
942
shape_vel_accel(vel_d_ms, accel_d_mss,
943
_vel_desired_ned_ms.z, _accel_desired_ned_mss.z,
944
-accel_max_d_mss, constrain_float(accel_max_d_mss, 0.0, 7.5),
945
jerk_max_d_msss, _dt_s, limit_output);
946
947
update_vel_accel(vel_d_ms, accel_d_mss, _dt_s, 0.0, 0.0);
948
}
949
950
// Generates a vertical trajectory using the given climb rate in cm/s and jerk-limited shaping.
951
// Adjusts the internal target altitude based on integrated climb rate.
952
// See set_pos_target_D_from_climb_rate_m() for full details.
953
void AC_PosControl::D_set_pos_target_from_climb_rate_cms(float climb_rate_cms)
954
{
955
D_set_pos_target_from_climb_rate_ms(climb_rate_cms * 0.01);
956
}
957
958
// Generates a vertical trajectory using the given climb rate in m/s and jerk-limited shaping.
959
// Target altitude is updated over time by integrating the climb rate.
960
void AC_PosControl::D_set_pos_target_from_climb_rate_ms(float climb_rate_ms, bool ignore_descent_limit)
961
{
962
if (ignore_descent_limit) {
963
// turn off limits in the down (positive z) direction
964
_limit_vector_ned.z = MIN(_limit_vector_ned.z, 0.0f);
965
}
966
967
float vel_d_ms = -climb_rate_ms;
968
input_vel_accel_D_m(vel_d_ms, 0.0);
969
}
970
971
// Sets vertical position, velocity, and acceleration in cm using jerk-limited shaping.
972
// See input_pos_vel_accel_D_m() for full details.
973
void AC_PosControl::input_pos_vel_accel_U_cm(float &pos_u_cm, float &vel_u_cms, float accel_u_cmss, bool limit_output)
974
{
975
float pos_d_m = -pos_u_cm * 0.01;
976
float vel_d_ms = -vel_u_cms * 0.01;
977
const float accel_d_mss = -accel_u_cmss * 0.01;
978
input_pos_vel_accel_D_m(pos_d_m, vel_d_ms, accel_d_mss, limit_output);
979
pos_u_cm = -pos_d_m * 100.0;
980
vel_u_cms = -vel_d_ms * 100.0;
981
}
982
983
// Sets vertical position, velocity, and acceleration in meters using jerk-limited shaping.
984
// Calculates required acceleration using current state and constraints.
985
// If `limit_output` is true, limits are applied to combined (desired + correction) command.
986
void AC_PosControl::input_pos_vel_accel_D_m(float &pos_d_m, float &vel_d_ms, float accel_d_mss, bool limit_output)
987
{
988
// calculated increased maximum acceleration and jerk if over speed
989
const float overspeed_gain = calculate_overspeed_gain();
990
const float accel_max_d_mss = _accel_max_d_mss * overspeed_gain;
991
const float jerk_max_d_msss = _jerk_max_d_msss * overspeed_gain;
992
993
// adjust desired altitude if motors have not hit their limits
994
update_pos_vel_accel(_pos_desired_ned_m.z, _vel_desired_ned_ms.z, _accel_desired_ned_mss.z, _dt_s, _limit_vector_ned.z, _p_pos_d_m.get_error(), _pid_vel_d_m.get_error());
995
996
shape_pos_vel_accel(pos_d_m, vel_d_ms, accel_d_mss,
997
_pos_desired_ned_m.z, _vel_desired_ned_ms.z, _accel_desired_ned_mss.z,
998
-_vel_max_up_ms, _vel_max_down_ms,
999
-accel_max_d_mss, constrain_float(accel_max_d_mss, 0.0, 7.5),
1000
jerk_max_d_msss, _dt_s, limit_output);
1001
1002
postype_t posp = pos_d_m;
1003
update_pos_vel_accel(posp, vel_d_ms, accel_d_mss, _dt_s, 0.0, 0.0, 0.0);
1004
pos_d_m = posp;
1005
}
1006
1007
// Sets target altitude in cm using jerk-limited shaping to gradually move to the new position.
1008
// See D_set_alt_target_with_slew_m() for full details.
1009
void AC_PosControl::set_alt_target_with_slew_cm(float pos_u_cm)
1010
{
1011
D_set_alt_target_with_slew_m(pos_u_cm * 0.01);
1012
}
1013
1014
// Sets target altitude in meters using jerk-limited shaping.
1015
void AC_PosControl::D_set_alt_target_with_slew_m(float pos_u_m)
1016
{
1017
float pos_d_m = -pos_u_m;
1018
float zero = 0;
1019
input_pos_vel_accel_D_m(pos_d_m, zero, 0);
1020
}
1021
1022
// Updates vertical (U) offsets by gradually moving them toward their targets.
1023
void AC_PosControl::D_update_offsets()
1024
{
1025
// Check if vertical offset targets have timed out
1026
uint32_t now_ms = AP_HAL::millis();
1027
if (now_ms - _posvelaccel_offset_target_d_ms > POSCONTROL_POSVELACCEL_OFFSET_TARGET_TIMEOUT_MS) {
1028
// Timeout: reset U-axis offset targets to zero
1029
_pos_offset_target_ned_m.z = 0.0;
1030
_vel_offset_target_ned_ms.z = 0.0;
1031
_accel_offset_target_ned_mss.z = 0.0;
1032
}
1033
1034
// Advance current offset state using PID-derived feedback and vertical limits
1035
postype_t p_offset_d_m = _pos_offset_ned_m.z;
1036
update_pos_vel_accel(p_offset_d_m, _vel_offset_ned_ms.z, _accel_offset_ned_mss.z, _dt_s, MIN(_limit_vector_ned.z, 0.0f), _p_pos_d_m.get_error(), _pid_vel_d_m.get_error());
1037
_pos_offset_ned_m.z = p_offset_d_m;
1038
1039
// Shape offset trajectory (position/velocity/acceleration) using jerk-limited smoothing
1040
shape_pos_vel_accel(_pos_offset_target_ned_m.z, _vel_offset_target_ned_ms.z, _accel_offset_target_ned_mss.z,
1041
_pos_offset_ned_m.z, _vel_offset_ned_ms.z, _accel_offset_ned_mss.z,
1042
-get_max_speed_up_ms(), get_max_speed_down_ms(),
1043
-D_get_max_accel_mss(), D_get_max_accel_mss(),
1044
_jerk_max_d_msss, _dt_s, false);
1045
1046
// Update target state forward in time with assumed zero velocity/acceleration targets
1047
p_offset_d_m = _pos_offset_target_ned_m.z;
1048
update_pos_vel_accel(p_offset_d_m, _vel_offset_target_ned_ms.z, _accel_offset_target_ned_mss.z, _dt_s, 0.0, 0.0, 0.0);
1049
_pos_offset_target_ned_m.z = p_offset_d_m;
1050
}
1051
1052
// Returns true if the U-axis controller has run in the last 5 control loop cycles.
1053
bool AC_PosControl::D_is_active() const
1054
{
1055
const uint32_t dt_ticks = AP::scheduler().ticks32() - _last_update_d_ticks;
1056
return dt_ticks <= 1;
1057
}
1058
1059
// Runs the vertical (U-axis) position controller.
1060
// Computes output acceleration based on position and velocity errors using PID correction.
1061
// Feedforward velocity and acceleration are combined with corrections to produce a smooth vertical command.
1062
// Desired position, velocity, and acceleration must be set before calling.
1063
void AC_PosControl::D_update_controller()
1064
{
1065
// check for ekf z-axis position reset
1066
D_handle_ekf_reset();
1067
1068
// Check for z_controller time out
1069
if (!D_is_active()) {
1070
D_init_controller();
1071
if (has_good_timing()) {
1072
// call internal error because initialisation has not been done
1073
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
1074
}
1075
}
1076
_last_update_d_ticks = AP::scheduler().ticks32();
1077
1078
// Update vertical offset targets and terrain estimate
1079
D_update_offsets();
1080
update_terrain();
1081
1082
// Position Controller
1083
1084
// Combine desired + offset + terrain for final position target
1085
_pos_target_ned_m.z = _pos_desired_ned_m.z + _pos_offset_ned_m.z + _pos_terrain_d_m;
1086
1087
// P controller: convert position error to velocity target
1088
_vel_target_ned_ms.z = _p_pos_d_m.update_all(_pos_target_ned_m.z, _pos_estimate_ned_m.z);
1089
_vel_target_ned_ms.z *= AP::ahrs().getControlScaleZ();
1090
1091
_pos_desired_ned_m.z = _pos_target_ned_m.z - (_pos_offset_ned_m.z + _pos_terrain_d_m);
1092
1093
// add feed forward component
1094
_vel_target_ned_ms.z += _vel_desired_ned_ms.z + _vel_offset_ned_ms.z + _vel_terrain_d_ms;
1095
1096
// Velocity Controller
1097
1098
// PID controller: convert velocity error to acceleration
1099
_accel_target_ned_mss.z = _pid_vel_d_m.update_all(_vel_target_ned_ms.z, _vel_estimate_ned_ms.z, _dt_s, _motors.limit.throttle_lower, _motors.limit.throttle_upper);
1100
_accel_target_ned_mss.z *= AP::ahrs().getControlScaleZ();
1101
1102
// add feed forward component
1103
_accel_target_ned_mss.z += _accel_desired_ned_mss.z + _accel_offset_ned_mss.z + _accel_terrain_d_mss;
1104
1105
// Acceleration Controller
1106
1107
// Gravity-compensated vertical acceleration measurement (positive = up)
1108
const float estimated_accel_d_mss = get_estimated_accel_D_mss();
1109
1110
// Ensure integrator can produce enough thrust to overcome hover throttle
1111
if (_motors.get_throttle_hover() > _pid_accel_d_m.imax()) {
1112
_pid_accel_d_m.set_imax(_motors.get_throttle_hover());
1113
}
1114
float thrust_d_norm;
1115
if (_vibe_comp_enabled) {
1116
// Use vibration-resistant throttle estimator (feedforward + scaled integrator)
1117
thrust_d_norm = get_throttle_with_vibration_override();
1118
} else {
1119
// Standard PID update using vertical acceleration error
1120
thrust_d_norm = _pid_accel_d_m.update_all(_accel_target_ned_mss.z, estimated_accel_d_mss, _dt_s, (_motors.limit.throttle_lower || _motors.limit.throttle_upper));
1121
// Include FF contribution to reduce delay
1122
thrust_d_norm += _pid_accel_d_m.get_ff();
1123
}
1124
thrust_d_norm -= _motors.get_throttle_hover();
1125
1126
// Actuator commands
1127
1128
// Send final throttle output to attitude controller (includes angle boost)
1129
_attitude_control.set_throttle_out(-thrust_d_norm, true, POSCONTROL_THROTTLE_CUTOFF_FREQ_HZ);
1130
1131
// Check for vertical controller health
1132
1133
// Update health indicator based on error magnitude vs configured speed range
1134
float error_ratio = _pid_vel_d_m.get_error() / _vel_max_down_ms;
1135
_vel_d_control_ratio += _dt_s * 0.1f * (0.5 - error_ratio);
1136
_vel_d_control_ratio = constrain_float(_vel_d_control_ratio, 0.0f, 2.0f);
1137
1138
// set vertical component of the limit vector
1139
if (_motors.limit.throttle_upper) {
1140
_limit_vector_ned.z = -1.0f;
1141
} else if (_motors.limit.throttle_lower) {
1142
_limit_vector_ned.z = 1.0f;
1143
} else {
1144
_limit_vector_ned.z = 0.0f;
1145
}
1146
}
1147
1148
1149
///
1150
/// Accessors
1151
///
1152
1153
// Returns the maximum allowed roll/pitch angle in radians.
1154
float AC_PosControl::get_lean_angle_max_rad() const
1155
{
1156
if (is_positive(_angle_max_override_rad)) {
1157
return _angle_max_override_rad;
1158
}
1159
if (!is_positive(_lean_angle_max_deg)) {
1160
return _attitude_control.lean_angle_max_rad();
1161
}
1162
return radians(_lean_angle_max_deg);
1163
}
1164
1165
// Sets externally computed NED position, velocity, and acceleration in meters, m/s, and m/s².
1166
// Use when path planning or shaping is done outside this controller.
1167
void AC_PosControl::set_pos_vel_accel_NED_m(const Vector3p& pos_ned_m, const Vector3f& vel_ned_ms, const Vector3f& accel_ned_mss)
1168
{
1169
_pos_desired_ned_m = pos_ned_m;
1170
_vel_desired_ned_ms = vel_ned_ms;
1171
_accel_desired_ned_mss = accel_ned_mss;
1172
}
1173
1174
// Sets externally computed NE position, velocity, and acceleration in meters, m/s, and m/s².
1175
// Use when path planning or shaping is done outside this controller.
1176
void AC_PosControl::set_pos_vel_accel_NE_m(const Vector2p& pos_ne_m, const Vector2f& vel_ne_ms, const Vector2f& accel_ne_mss)
1177
{
1178
_pos_desired_ned_m.xy() = pos_ne_m;
1179
_vel_desired_ned_ms.xy() = vel_ne_ms;
1180
_accel_desired_ned_mss.xy() = accel_ne_mss;
1181
}
1182
1183
// Converts lean angles (rad) to NED acceleration in m/s².
1184
Vector3f AC_PosControl::lean_angles_rad_to_accel_NED_mss(const Vector3f& att_target_euler_rad) const
1185
{
1186
// rotate our roll, pitch angles into lat/lon frame
1187
const float sin_roll = sinf(att_target_euler_rad.x);
1188
const float cos_roll = cosf(att_target_euler_rad.x);
1189
const float sin_pitch = sinf(att_target_euler_rad.y);
1190
const float cos_pitch = cosf(att_target_euler_rad.y);
1191
const float sin_yaw = sinf(att_target_euler_rad.z);
1192
const float cos_yaw = cosf(att_target_euler_rad.z);
1193
1194
return Vector3f{
1195
GRAVITY_MSS * (-cos_yaw * sin_pitch * cos_roll - sin_yaw * sin_roll) / MAX(cos_roll * cos_pitch, 0.1f),
1196
GRAVITY_MSS * (-sin_yaw * sin_pitch * cos_roll + cos_yaw * sin_roll) / MAX(cos_roll * cos_pitch, 0.1f),
1197
-GRAVITY_MSS
1198
};
1199
}
1200
1201
/// Terrain
1202
1203
// Initializes terrain position, velocity, and acceleration to match the terrain target.
1204
void AC_PosControl::init_terrain()
1205
{
1206
// set terrain position and target to zero
1207
_pos_terrain_target_d_m = 0.0;
1208
_pos_terrain_d_m = 0.0;
1209
1210
// set velocity offset to zero
1211
_vel_terrain_d_ms = 0.0;
1212
1213
// set acceleration offset to zero
1214
_accel_terrain_d_mss = 0.0;
1215
}
1216
1217
// Initializes both the terrain altitude and terrain target to the same value
1218
// (altitude above EKF origin in centimeters, Up-positive).
1219
// See init_pos_terrain_D_m() for full description.
1220
void AC_PosControl::init_pos_terrain_U_cm(float pos_terrain_u_cm)
1221
{
1222
init_pos_terrain_D_m(-pos_terrain_u_cm * 0.01);
1223
}
1224
1225
// Initializes both the terrain altitude and terrain target to the same value
1226
// (relative to EKF origin in meters, Down-positive).
1227
void AC_PosControl::init_pos_terrain_D_m(float pos_terrain_d_m)
1228
{
1229
_pos_desired_ned_m.z -= (pos_terrain_d_m - _pos_terrain_d_m);
1230
_pos_terrain_target_d_m = pos_terrain_d_m;
1231
_pos_terrain_d_m = pos_terrain_d_m;
1232
}
1233
1234
1235
/// Offsets
1236
1237
// Initializes NE position/velocity/acceleration offsets to match their respective targets.
1238
void AC_PosControl::NE_init_offsets()
1239
{
1240
// check for offset target timeout
1241
uint32_t now_ms = AP_HAL::millis();
1242
if (now_ms - _posvelaccel_offset_target_ne_ms > POSCONTROL_POSVELACCEL_OFFSET_TARGET_TIMEOUT_MS) {
1243
_pos_offset_target_ned_m.xy().zero();
1244
_vel_offset_target_ned_ms.xy().zero();
1245
_accel_offset_target_ned_mss.xy().zero();
1246
}
1247
1248
// set position offset to target
1249
_pos_offset_ned_m.xy() = _pos_offset_target_ned_m.xy();
1250
1251
// set velocity offset to target
1252
_vel_offset_ned_ms.xy() = _vel_offset_target_ned_ms.xy();
1253
1254
// set acceleration offset to target
1255
_accel_offset_ned_mss.xy() = _accel_offset_target_ned_mss.xy();
1256
}
1257
1258
// Initializes vertical (U) offsets to match their respective targets.
1259
void AC_PosControl::D_init_offsets()
1260
{
1261
// check for offset target timeout
1262
uint32_t now_ms = AP_HAL::millis();
1263
if (now_ms - _posvelaccel_offset_target_d_ms > POSCONTROL_POSVELACCEL_OFFSET_TARGET_TIMEOUT_MS) {
1264
_pos_offset_target_ned_m.z = 0.0;
1265
_vel_offset_target_ned_ms.z = 0.0;
1266
_accel_offset_target_ned_mss.z = 0.0;
1267
}
1268
1269
// set position offset to target
1270
_pos_offset_ned_m.z = _pos_offset_target_ned_m.z;
1271
1272
// set velocity offset to target
1273
_vel_offset_ned_ms.z = _vel_offset_target_ned_ms.z;
1274
1275
// set acceleration offset to target
1276
_accel_offset_ned_mss.z = _accel_offset_target_ned_mss.z;
1277
}
1278
1279
#if AP_SCRIPTING_ENABLED
1280
// Sets additional position, velocity, and acceleration offsets in meters (NED frame) for scripting.
1281
// Offsets are added to the controller’s internal target.
1282
// Used in LUA
1283
bool AC_PosControl::set_posvelaccel_offset(const Vector3f &pos_offset_ned_m, const Vector3f &vel_offset_ned_ms, const Vector3f &accel_offset_ned_mss)
1284
{
1285
set_posvelaccel_offset_target_NE_m(pos_offset_ned_m.topostype().xy(), vel_offset_ned_ms.xy(), accel_offset_ned_mss.xy());
1286
set_posvelaccel_offset_target_D_m(pos_offset_ned_m.topostype().z, vel_offset_ned_ms.z, accel_offset_ned_mss.z);
1287
return true;
1288
}
1289
1290
// Retrieves current scripted offsets in meters (NED frame).
1291
// Used in LUA
1292
bool AC_PosControl::get_posvelaccel_offset(Vector3f &pos_offset_ned_m, Vector3f &vel_offset_ned_ms, Vector3f &accel_offset_ned_mss)
1293
{
1294
pos_offset_ned_m = _pos_offset_target_ned_m.tofloat();
1295
vel_offset_ned_ms = _vel_offset_target_ned_ms;
1296
accel_offset_ned_mss = _accel_offset_target_ned_mss;
1297
return true;
1298
}
1299
1300
// Retrieves current target velocity (NED frame, m/s) including any scripted offset.
1301
// Used in LUA
1302
bool AC_PosControl::get_vel_target(Vector3f &vel_target_ned_ms)
1303
{
1304
if (!NE_is_active() || !D_is_active()) {
1305
return false;
1306
}
1307
1308
vel_target_ned_ms = _vel_target_ned_ms;
1309
return true;
1310
}
1311
1312
// Retrieves current target acceleration (NED frame, m/s²) including any scripted offset.
1313
// Used in LUA
1314
bool AC_PosControl::get_accel_target(Vector3f &accel_target_ned_mss)
1315
{
1316
if (!NE_is_active() || !D_is_active()) {
1317
return false;
1318
}
1319
1320
accel_target_ned_mss = _accel_target_ned_mss;
1321
return true;
1322
}
1323
#endif
1324
1325
// Sets NE offset targets in meters, m/s, and m/s².
1326
void AC_PosControl::set_posvelaccel_offset_target_NE_m(const Vector2p& pos_offset_target_ne_m, const Vector2f& vel_offset_target_ne_ms, const Vector2f& accel_offset_target_ne_mss)
1327
{
1328
// set position offset target
1329
_pos_offset_target_ned_m.xy() = pos_offset_target_ne_m;
1330
1331
// set velocity offset target
1332
_vel_offset_target_ned_ms.xy() = vel_offset_target_ne_ms;
1333
1334
// set acceleration offset target
1335
_accel_offset_target_ned_mss.xy() = accel_offset_target_ne_mss;
1336
1337
// record time of update so we can detect timeouts
1338
_posvelaccel_offset_target_ne_ms = AP_HAL::millis();
1339
}
1340
1341
// Sets vertical offset targets (m, m/s, m/s²) relative to EKF origin in meters, Down-positive.
1342
void AC_PosControl::set_posvelaccel_offset_target_D_m(float pos_offset_target_d_m, float vel_offset_target_d_ms, const float accel_offset_target_d_mss)
1343
{
1344
// set position offset target
1345
_pos_offset_target_ned_m.z = pos_offset_target_d_m;
1346
1347
// set velocity offset target
1348
_vel_offset_target_ned_ms.z = vel_offset_target_d_ms;
1349
1350
// set acceleration offset target
1351
_accel_offset_target_ned_mss.z = accel_offset_target_d_mss;
1352
1353
// record time of update so we can detect timeouts
1354
_posvelaccel_offset_target_d_ms = AP_HAL::millis();
1355
}
1356
1357
// Returns desired thrust direction as a unit vector in the body frame.
1358
Vector3f AC_PosControl::get_thrust_vector() const
1359
{
1360
Vector3f accel_target_ned_mss = get_accel_target_NED_mss();
1361
accel_target_ned_mss.z = -GRAVITY_MSS;
1362
return accel_target_ned_mss;
1363
}
1364
1365
// Computes NE stopping point in meters based on current position, velocity, and acceleration.
1366
void AC_PosControl::get_stopping_point_NE_m(Vector2p &stopping_point_ne_m) const
1367
{
1368
// Start from estimated NE position with offset removed
1369
// todo: we should use the current target position and velocity if we are currently running the position controller
1370
stopping_point_ne_m = _pos_estimate_ned_m.xy();
1371
stopping_point_ne_m -= _pos_offset_ned_m.xy();
1372
1373
Vector2f vel_estimate_ne_ms = _vel_estimate_ned_ms.xy();
1374
vel_estimate_ne_ms -= _vel_offset_ned_ms.xy();
1375
1376
// Compute velocity magnitude
1377
float speed_ne_ms = vel_estimate_ne_ms.length();
1378
1379
if (!is_positive(speed_ne_ms)) {
1380
return;
1381
}
1382
1383
// Use current P gain and max accel to estimate stopping distance
1384
float kP = _p_pos_ne_m.kP();
1385
const float stopping_dist_m = stopping_distance(constrain_float(speed_ne_ms, 0.0, _vel_max_ne_ms), kP, _accel_max_ne_mss);
1386
if (!is_positive(stopping_dist_m)) {
1387
return;
1388
}
1389
1390
// Project stopping distance along current velocity direction
1391
// todo: convert velocity to a unit vector instead.
1392
const float stopping_time_s = stopping_dist_m / speed_ne_ms;
1393
stopping_point_ne_m += (vel_estimate_ne_ms * stopping_time_s).topostype();
1394
}
1395
1396
// Computes vertical stopping point in meters based on current velocity and acceleration.
1397
void AC_PosControl::get_stopping_point_D_m(postype_t &stopping_point_d_m) const
1398
{
1399
float curr_pos_d_m = _pos_estimate_ned_m.z;
1400
curr_pos_d_m -= _pos_offset_ned_m.z;
1401
1402
float curr_vel_d_ms = _vel_estimate_ned_ms.z;
1403
curr_vel_d_ms -= _vel_offset_ned_ms.z;
1404
1405
// If controller is unconfigured or disabled, return current position
1406
if (!is_positive(_p_pos_d_m.kP()) || !is_positive(_accel_max_d_mss)) {
1407
stopping_point_d_m = curr_pos_d_m;
1408
return;
1409
}
1410
1411
// Estimate stopping point using current velocity, P gain, and max vertical acceleration
1412
stopping_point_d_m = curr_pos_d_m + constrain_float(stopping_distance(curr_vel_d_ms, _p_pos_d_m.kP(), _accel_max_d_mss), - POSCONTROL_STOPPING_DIST_UP_MAX_M, POSCONTROL_STOPPING_DIST_DOWN_MAX_M);
1413
}
1414
1415
// Returns bearing from current position to position target in radians.
1416
// 0 = North, positive = clockwise.
1417
float AC_PosControl::get_bearing_to_target_rad() const
1418
{
1419
return (_pos_target_ned_m.xy() - _pos_estimate_ned_m.xy()).angle();
1420
}
1421
1422
1423
///
1424
/// System methods
1425
///
1426
1427
// Updates internal NED position and velocity estimates from AHRS.
1428
// Falls back to vertical-only data if horizontal velocity or position is invalid or vibration forces it.
1429
// When high_vibes is true, forces use of vertical fallback for velocity.
1430
void AC_PosControl::update_estimates(bool high_vibes)
1431
{
1432
Vector3p pos_estimate_ned_m;
1433
if (!AP::ahrs().get_relative_position_NED_origin(pos_estimate_ned_m)) {
1434
float posD;
1435
if (AP::ahrs().get_relative_position_D_origin_float(posD)) {
1436
pos_estimate_ned_m.z = posD;
1437
}
1438
}
1439
_pos_estimate_ned_m = pos_estimate_ned_m;
1440
1441
Vector3f vel_estimate_ned_ms;
1442
if (!AP::ahrs().get_velocity_NED(vel_estimate_ned_ms) || high_vibes) {
1443
float rate_z;
1444
if (AP::ahrs().get_vert_pos_rate_D(rate_z)) {
1445
vel_estimate_ned_ms.z = rate_z;
1446
}
1447
}
1448
_vel_estimate_ned_ms = vel_estimate_ned_ms;
1449
}
1450
1451
// Calculates vertical throttle using vibration-resistant feedforward estimation.
1452
// Returns throttle output using manual feedforward gain for vibration compensation mode.
1453
// Integrator is adjusted using velocity error when PID is being overridden.
1454
float AC_PosControl::get_throttle_with_vibration_override()
1455
{
1456
const float thr_per_accel_d_mss = _motors.get_throttle_hover();
1457
// Estimate throttle based on desired acceleration (manual feedforward gain).
1458
// Used when IMU vibrations corrupt raw acceleration measurements.
1459
// Allow integrator to compensate for velocity error only if not thrust-limited,
1460
// or if integrator is actively helping counteract velocity error direction.
1461
// ToDo: clear pid_info P, I and D terms for logging
1462
if (!(_motors.limit.throttle_lower || _motors.limit.throttle_upper) || ((is_positive(_pid_accel_d_m.get_i()) && is_negative(_pid_vel_d_m.get_error())) || (is_negative(_pid_accel_d_m.get_i()) && is_positive(_pid_vel_d_m.get_error())))) {
1463
// Adjust integrator to help reduce velocity error.
1464
// Note: scale by velocity P-gain and an override-specific I gain.
1465
_pid_accel_d_m.set_integrator(_pid_accel_d_m.get_i() + _dt_s * thr_per_accel_d_mss * _pid_vel_d_m.get_error() * _pid_vel_d_m.kP() * POSCONTROL_VIBE_COMP_I_GAIN);
1466
}
1467
// Final throttle = P term (feedforward) + scaled I term.
1468
return POSCONTROL_VIBE_COMP_P_GAIN * thr_per_accel_d_mss * _accel_target_ned_mss.z + _pid_accel_d_m.get_i();
1469
}
1470
1471
// Resets NED position controller state to prevent transients when exiting standby.
1472
// Zeros I-terms and aligns targets to current position.
1473
void AC_PosControl::NED_standby_reset()
1474
{
1475
// Reset vertical acceleration controller integrator to prevent throttle bias on reentry
1476
_pid_accel_d_m.set_integrator(0.0f);
1477
1478
// Reset position controller targets to match current estimate — avoids position jumps
1479
_pos_target_ned_m = _pos_estimate_ned_m;
1480
1481
// Reset horizontal velocity controller integrator and derivative filter
1482
_pid_vel_ne_m.reset_filter();
1483
1484
// Reset EKF XY position reset tracking for NE controller
1485
NE_init_ekf_reset();
1486
}
1487
1488
#if HAL_LOGGING_ENABLED
1489
// Writes position controller diagnostic logs (PSCN, PSCE, etc).
1490
void AC_PosControl::write_log()
1491
{
1492
if (NE_is_active()) {
1493
float accel_n_mss, accel_e_mss;
1494
lean_angles_to_accel_NE_mss(accel_n_mss, accel_e_mss);
1495
1496
// Log North-axis position control (PSCN): desired, target, and actual
1497
Write_PSCN(_pos_desired_ned_m.x, _pos_target_ned_m.x, _pos_estimate_ned_m.x ,
1498
_vel_desired_ned_ms.x, _vel_target_ned_ms.x, _vel_estimate_ned_ms.x,
1499
_accel_desired_ned_mss.x, _accel_target_ned_mss.x, accel_n_mss);
1500
1501
// Log East-axis position control (PSCE): desired, target, and actual
1502
Write_PSCE(_pos_desired_ned_m.y, _pos_target_ned_m.y, _pos_estimate_ned_m.y,
1503
_vel_desired_ned_ms.y, _vel_target_ned_ms.y, _vel_estimate_ned_ms.y,
1504
_accel_desired_ned_mss.y, _accel_target_ned_mss.y, accel_e_mss);
1505
1506
// log offsets if they are being used
1507
if (!_pos_offset_ned_m.xy().is_zero()) {
1508
// Log North offset tracking (PSON)
1509
Write_PSON(_pos_offset_target_ned_m.x, _pos_offset_ned_m.x, _vel_offset_target_ned_ms.x, _vel_offset_ned_ms.x, _accel_offset_target_ned_mss.x, _accel_offset_ned_mss.x);
1510
1511
// Log East offset tracking (PSOE)
1512
Write_PSOE(_pos_offset_target_ned_m.y, _pos_offset_ned_m.y, _vel_offset_target_ned_ms.y, _vel_offset_ned_ms.y, _accel_offset_target_ned_mss.y, _accel_offset_ned_mss.y);
1513
}
1514
}
1515
1516
if (D_is_active()) {
1517
// Log Down-axis position control (PSCD)
1518
Write_PSCD(_pos_desired_ned_m.z, _pos_target_ned_m.z, _pos_estimate_ned_m.z,
1519
_vel_desired_ned_ms.z, _vel_target_ned_ms.z, _vel_estimate_ned_ms.z,
1520
_accel_desired_ned_mss.z, _accel_target_ned_mss.z, get_estimated_accel_D_mss());
1521
1522
// log down and terrain offsets if they are being used
1523
if (!is_zero(_pos_offset_ned_m.z)) {
1524
// Log Down offset tracking (PSOD)
1525
Write_PSOD(_pos_offset_target_ned_m.z, _pos_offset_ned_m.z, _vel_offset_target_ned_ms.z, _vel_offset_ned_ms.z, _accel_offset_target_ned_mss.z, _accel_offset_ned_mss.z);
1526
}
1527
if (!is_zero(_pos_terrain_d_m)) {
1528
// Log terrain-following offset (PSOT)
1529
Write_PSOT(_pos_terrain_target_d_m, _pos_terrain_d_m, 0, _vel_terrain_d_ms, 0, _accel_terrain_d_mss);
1530
}
1531
}
1532
}
1533
#endif // HAL_LOGGING_ENABLED
1534
1535
// Returns lateral distance to closest point on active trajectory in meters.
1536
// Used to assess horizontal deviation from path.
1537
float AC_PosControl::crosstrack_error_m() const
1538
{
1539
const Vector2f pos_error = (_pos_target_ned_m.xy() - _pos_estimate_ned_m.xy()).tofloat();
1540
if (is_zero(_vel_desired_ned_ms.xy().length_squared())) {
1541
// No desired velocity → return direct distance to target
1542
return pos_error.length();
1543
} else {
1544
// Project position error onto desired velocity vector
1545
const Vector2f vel_unit = _vel_desired_ned_ms.xy().normalized();
1546
const float dot_error = pos_error * vel_unit;
1547
1548
// Use Pythagorean difference to isolate perpendicular (cross-track) component
1549
// todo: remove MAX of zero when safe_sqrt fixed
1550
return safe_sqrt(MAX(pos_error.length_squared() - sq(dot_error), 0.0));
1551
}
1552
}
1553
1554
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
1555
// Returns true if the requested forward pitch is limited by the configured tilt constraint.
1556
bool AC_PosControl::get_fwd_pitch_is_limited() const
1557
{
1558
if (_limit_vector_ned.xy().is_zero()) {
1559
return false;
1560
}
1561
const float angle_max_rad = MIN(_attitude_control.get_althold_lean_angle_max_rad(), get_lean_angle_max_rad());
1562
const float accel_max_mss = angle_rad_to_accel_mss(angle_max_rad);
1563
// Check for pitch limiting in the forward direction
1564
const float accel_fwd_unlimited_mss = _limit_vector_ned.x * _ahrs.cos_yaw() + _limit_vector_ned.y * _ahrs.sin_yaw();
1565
const float pitch_target_unlimited_deg = accel_mss_to_angle_deg(- MIN(accel_fwd_unlimited_mss, accel_max_mss));
1566
const float accel_fwd_limited = _accel_target_ned_mss.x * _ahrs.cos_yaw() + _accel_target_ned_mss.y * _ahrs.sin_yaw();
1567
const float pitch_target_limited_deg = accel_mss_to_angle_deg(- accel_fwd_limited);
1568
1569
return is_negative(pitch_target_unlimited_deg) && pitch_target_unlimited_deg < pitch_target_limited_deg;
1570
}
1571
#endif // APM_BUILD_TYPE(APM_BUILD_ArduPlane)
1572
1573
///
1574
/// private methods
1575
///
1576
1577
/// Terrain
1578
1579
// Updates terrain estimate (_pos_terrain_d_m) toward target using filter time constants.
1580
void AC_PosControl::update_terrain()
1581
{
1582
// update position, velocity, acceleration offsets for this iteration
1583
postype_t pos_terrain_d_m = _pos_terrain_d_m;
1584
update_pos_vel_accel(pos_terrain_d_m, _vel_terrain_d_ms, _accel_terrain_d_mss, _dt_s, MIN(_limit_vector_ned.z, 0.0f), _p_pos_d_m.get_error(), _pid_vel_d_m.get_error());
1585
_pos_terrain_d_m = pos_terrain_d_m;
1586
1587
// input shape horizontal position, velocity and acceleration offsets
1588
shape_pos_vel_accel(_pos_terrain_target_d_m, 0.0, 0.0,
1589
_pos_terrain_d_m, _vel_terrain_d_ms, _accel_terrain_d_mss,
1590
-get_max_speed_up_ms(), get_max_speed_down_ms(),
1591
-D_get_max_accel_mss(), D_get_max_accel_mss(),
1592
_jerk_max_d_msss, _dt_s, false);
1593
1594
// we do not have to update _pos_terrain_target_d_m because we assume the target velocity and acceleration are zero
1595
// if we know how fast the terrain altitude is changing we would add update_pos_vel_accel for _pos_terrain_target_d_m here
1596
}
1597
1598
// Converts horizontal acceleration (m/s²) to roll/pitch lean angles in radians.
1599
void AC_PosControl::accel_NE_mss_to_lean_angles_rad(float accel_n_mss, float accel_e_mss, float& roll_target_rad, float& pitch_target_rad) const
1600
{
1601
// rotate accelerations into body forward-right frame
1602
const float accel_forward_mss = accel_n_mss * _ahrs.cos_yaw() + accel_e_mss * _ahrs.sin_yaw();
1603
const float accel_right_mss = -accel_n_mss * _ahrs.sin_yaw() + accel_e_mss * _ahrs.cos_yaw();
1604
1605
// update angle targets that will be passed to stabilize controller
1606
pitch_target_rad = accel_mss_to_angle_rad(-accel_forward_mss);
1607
float cos_pitch_target = cosf(pitch_target_rad);
1608
roll_target_rad = accel_mss_to_angle_rad(accel_right_mss * cos_pitch_target);
1609
}
1610
1611
// Converts current target lean angles to NE acceleration in m/s².
1612
void AC_PosControl::lean_angles_to_accel_NE_mss(float& accel_n_mss, float& accel_e_mss) const
1613
{
1614
// rotate our roll, pitch angles into lat/lon frame
1615
Vector3f att_target_euler_rad = _attitude_control.get_att_target_euler_rad();
1616
att_target_euler_rad.z = _ahrs.yaw;
1617
Vector3f accel_ne_mss = lean_angles_rad_to_accel_NED_mss(att_target_euler_rad);
1618
1619
accel_n_mss = accel_ne_mss.x;
1620
accel_e_mss = accel_ne_mss.y;
1621
}
1622
1623
// Computes desired yaw and yaw rate based on the NE acceleration and velocity vectors.
1624
// Aligns yaw with the direction of travel if speed exceeds 5% of maximum.
1625
void AC_PosControl::calculate_yaw_and_rate_yaw()
1626
{
1627
// Calculate the turn rate
1628
float turn_rate_rads = 0.0f;
1629
const float vel_desired_length_ne_ms = _vel_desired_ned_ms.xy().length();
1630
if (is_positive(vel_desired_length_ne_ms)) {
1631
// Project acceleration vector into velocity direction to extract forward acceleration component
1632
const float accel_forward_mss = (_accel_desired_ned_mss.x * _vel_desired_ned_ms.x + _accel_desired_ned_mss.y * _vel_desired_ned_ms.y) / vel_desired_length_ne_ms;
1633
// Subtract forward component to isolate turn acceleration perpendicular to velocity vector
1634
const Vector2f accel_turn_ne_mss = _accel_desired_ned_mss.xy() - _vel_desired_ned_ms.xy() * accel_forward_mss / vel_desired_length_ne_ms;
1635
// Compute turn rate from lateral acceleration and velocity (centripetal formula)
1636
const float accel_turn_length_ne_mss = accel_turn_ne_mss.length();
1637
turn_rate_rads = accel_turn_length_ne_mss / vel_desired_length_ne_ms;
1638
// Determine turn direction: positive = clockwise (right)
1639
if ((accel_turn_ne_mss.y * _vel_desired_ned_ms.x - accel_turn_ne_mss.x * _vel_desired_ned_ms.y) < 0.0) {
1640
turn_rate_rads = -turn_rate_rads;
1641
}
1642
}
1643
1644
// If vehicle is moving significantly, align yaw to velocity vector and apply computed turn rate
1645
if (vel_desired_length_ne_ms > _vel_max_ne_ms * 0.05f) {
1646
_yaw_target_rad = _vel_desired_ned_ms.xy().angle();
1647
_yaw_rate_target_rads = turn_rate_rads;
1648
return;
1649
}
1650
1651
// If motion is too slow, retain last yaw target from attitude controller
1652
_yaw_target_rad = _attitude_control.get_att_target_euler_rad().z;
1653
_yaw_rate_target_rads = 0;
1654
}
1655
1656
// Computes scaling factor to increase max vertical accel/jerk if vertical speed exceeds configured limits.
1657
float AC_PosControl::calculate_overspeed_gain()
1658
{
1659
// If desired descent speed exceeds configured max, scale acceleration/jerk proportionally
1660
if (_vel_desired_ned_ms.z > _vel_max_down_ms && !is_zero(_vel_max_down_ms)) {
1661
return POSCONTROL_OVERSPEED_GAIN_U * _vel_desired_ned_ms.z / _vel_max_down_ms;
1662
}
1663
1664
// If desired climb speed exceeds configured max, scale acceleration/jerk proportionally
1665
if (_vel_desired_ned_ms.z < -_vel_max_up_ms && !is_zero(_vel_max_up_ms)) {
1666
return -POSCONTROL_OVERSPEED_GAIN_U * _vel_desired_ned_ms.z / _vel_max_up_ms;
1667
}
1668
1669
// Within normal speed limits — use nominal acceleration and jerk
1670
return 1.0;
1671
}
1672
1673
// Initializes tracking of NE EKF position resets.
1674
void AC_PosControl::NE_init_ekf_reset()
1675
{
1676
Vector2f pos_shift;
1677
_ekf_ne_reset_ms = _ahrs.getLastPosNorthEastReset(pos_shift);
1678
}
1679
1680
// Handles NE position reset detection and response (e.g., clearing accumulated errors).
1681
void AC_PosControl::NE_handle_ekf_reset()
1682
{
1683
// Check for EKF-reported NE position shift since last update
1684
Vector2f pos_shift_ne_m;
1685
uint32_t reset_ms = _ahrs.getLastPosNorthEastReset(pos_shift_ne_m);
1686
// todo: the actual difference in position and velocity estimation.
1687
// This will prevent the need to pause error calculation for one cycle.
1688
1689
if (reset_ms != _ekf_ne_reset_ms) {
1690
// This ensures controller output remains continuous after EKF realigns the origin.
1691
1692
// Reconstruct position target relative to the to new EKF estimation to maintain the current position error
1693
Vector2p delta_pos_estimate_ne_m = _p_pos_ne_m.get_error().topostype() - (_pos_target_ned_m.xy() - _pos_estimate_ned_m.xy());
1694
_pos_target_ned_m.xy() += delta_pos_estimate_ne_m;
1695
1696
// Reconstruct velocity target relative to the to new EKF estimation to maintain the current velocity error
1697
Vector2f delta_vel_estimate_ne_ms = _pid_vel_ne_m.get_error() - (_vel_target_ned_ms.xy() - _vel_estimate_ned_ms.xy());
1698
_vel_target_ned_ms.xy() += delta_vel_estimate_ne_ms;
1699
1700
switch (_ekf_reset_method) {
1701
case EKFResetMethod::MoveTarget:
1702
// Reset NE controller desired position and velocity to preserve actual position control during Loiter, PosHold, etc.
1703
_pos_desired_ned_m.xy() += delta_pos_estimate_ne_m;
1704
_vel_desired_ned_ms.xy() += delta_vel_estimate_ne_ms;
1705
break;
1706
case EKFResetMethod::MoveVehicle:
1707
// Move the change in estimate into the offsest to move the aircraft to our new estimate smoothly during Auto, Guided, etc.
1708
_pos_offset_ned_m.xy() += delta_pos_estimate_ne_m;
1709
_vel_offset_ned_ms.xy() += delta_vel_estimate_ne_ms;
1710
break;
1711
}
1712
_ekf_ne_reset_ms = reset_ms;
1713
}
1714
}
1715
1716
// Initializes tracking of vertical (U) EKF resets.
1717
void AC_PosControl::D_init_ekf_reset()
1718
{
1719
float alt_shift_d_m;
1720
_ekf_d_reset_ms = _ahrs.getLastPosDownReset(alt_shift_d_m);
1721
}
1722
1723
// Handles U EKF reset detection and response.
1724
void AC_PosControl::D_handle_ekf_reset()
1725
{
1726
// Check for EKF-reported Down-axis shift since last update
1727
float pos_shift_d_m;
1728
uint32_t reset_ms = _ahrs.getLastPosDownReset(pos_shift_d_m);
1729
// todo: the actual difference in position and velocity estimation.
1730
// This will prevent the need to pause error calculation for one cycle.
1731
1732
if (reset_ms != 0 && reset_ms != _ekf_d_reset_ms) {
1733
// This ensures controller output remains continuous after EKF realigns the origin.
1734
// Reconstruct position target relative to the to new EKF estimation to maintain the current position error
1735
postype_t delta_pos_estimate_d_m = _p_pos_d_m.get_error() - (_pos_target_ned_m.z - _pos_estimate_ned_m.z);
1736
_pos_target_ned_m.z += delta_pos_estimate_d_m;
1737
1738
// Reconstruct velocity target relative to the to new EKF estimation to maintain the current velocity error
1739
float delta_vel_estimate_d_ms = _pid_vel_d_m.get_error() - (_vel_target_ned_ms.z - _vel_estimate_ned_ms.z);
1740
_vel_target_ned_ms.z += delta_vel_estimate_d_ms;
1741
1742
switch (_ekf_reset_method) {
1743
case EKFResetMethod::MoveTarget:
1744
// Reset U controller desired position and velocity to preserve actual position control during Loiter, PosHold, etc.
1745
_pos_desired_ned_m.z += delta_pos_estimate_d_m;
1746
_vel_desired_ned_ms.z += delta_vel_estimate_d_ms;
1747
break;
1748
case EKFResetMethod::MoveVehicle:
1749
// Move the change in estimate into the offsest to move the aircraft to our new estimate smoothly during Auto, Guided, etc.
1750
_pos_offset_ned_m.z += delta_pos_estimate_d_m;
1751
_vel_offset_ned_ms.z += delta_vel_estimate_d_ms;
1752
break;
1753
}
1754
_ekf_d_reset_ms = reset_ms;
1755
}
1756
}
1757
1758
// Performs pre-arm checks for position control parameters and EKF readiness.
1759
// Returns false if failure_msg is populated.
1760
bool AC_PosControl::pre_arm_checks(const char *param_prefix,
1761
char *failure_msg,
1762
const uint8_t failure_msg_len)
1763
{
1764
if (!is_positive(NE_get_pos_p().kP())) {
1765
hal.util->snprintf(failure_msg, failure_msg_len, "%s_NE_POS_P must be > 0", param_prefix);
1766
return false;
1767
}
1768
if (!is_positive(D_get_pos_p().kP())) {
1769
hal.util->snprintf(failure_msg, failure_msg_len, "%s_D_POS_P must be > 0", param_prefix);
1770
return false;
1771
}
1772
if (!is_positive(D_get_vel_pid().kP())) {
1773
hal.util->snprintf(failure_msg, failure_msg_len, "%s_D_VEL_P must be > 0", param_prefix);
1774
return false;
1775
}
1776
if (!is_positive(D_get_accel_pid().kP())) {
1777
hal.util->snprintf(failure_msg, failure_msg_len, "%s_D_ACC_P must be > 0", param_prefix);
1778
return false;
1779
}
1780
if (!is_positive(D_get_accel_pid().kI())) {
1781
hal.util->snprintf(failure_msg, failure_msg_len, "%s_D_ACC_I must be > 0", param_prefix);
1782
return false;
1783
}
1784
1785
return true;
1786
}
1787
1788
// return true if on a real vehicle or SITL with lock-step scheduling
1789
bool AC_PosControl::has_good_timing(void) const
1790
{
1791
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1792
auto *sitl = AP::sitl();
1793
if (sitl) {
1794
return sitl->state.is_lock_step_scheduled;
1795
}
1796
#endif
1797
// real boards are assumed to have good timing
1798
return true;
1799
}
1800
1801
// perform any required parameter conversions
1802
void AC_PosControl::convert_parameters()
1803
{
1804
// find param table key
1805
uint16_t k_param_psc_key;
1806
if (!AP_Param::find_key_by_pointer(this, k_param_psc_key)) {
1807
return;
1808
}
1809
1810
// return immediately if parameter conversion has already been performed
1811
if (_pid_accel_d_m.kP().configured()) {
1812
return;
1813
}
1814
1815
// PARAMETER_CONVERSION - Added: Nov-2025 for 4.7
1816
// parameters that are simply moved
1817
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
1818
static const AP_Param::ConversionInfo conversion_info[] = {
1819
{ k_param_psc_key, 258257, AP_PARAM_FLOAT, "Q_P_D_VEL_P" }, // Q_P_VELZ_P moved to Q_P_D_VEL_P
1820
{ k_param_psc_key, 4305, AP_PARAM_FLOAT, "Q_P_D_VEL_I" }, // Q_P_VELZ_I moved to Q_P_D_VEL_I
1821
{ k_param_psc_key, 16593, AP_PARAM_FLOAT, "Q_P_D_VEL_D" }, // Q_P_VELZ_D moved to Q_P_D_VEL_D
1822
{ k_param_psc_key, 12497, AP_PARAM_FLOAT, "Q_P_D_VEL_FLTE" }, // Q_P_VELZ_FLTE moved to Q_P_D_VEL_FLTE
1823
{ k_param_psc_key, 20689, AP_PARAM_FLOAT, "Q_P_D_VEL_FLTD" }, // Q_P_VELZ_FLTD moved to Q_P_D_VEL_FLTD
1824
{ k_param_psc_key, 24785, AP_PARAM_FLOAT, "Q_P_D_VEL_FF" }, // Q_P_VELZ_FF moved to Q_P_D_VEL_FF
1825
{ k_param_psc_key, 16657, AP_PARAM_FLOAT, "Q_P_D_ACC_FF" }, // Q_P_ACCZ_FF moved to Q_P_D_ACC_FF
1826
{ k_param_psc_key, 37137, AP_PARAM_FLOAT, "Q_P_D_ACC_FLTT" }, // Q_P_ACCZ_FLTT moved to Q_P_D_ACC_FLTT
1827
{ k_param_psc_key, 41233, AP_PARAM_FLOAT, "Q_P_D_ACC_FLTE" }, // Q_P_ACCZ_FLTE moved to Q_P_D_ACC_FLTE
1828
{ k_param_psc_key, 45329, AP_PARAM_FLOAT, "Q_P_D_ACC_FLTD" }, // Q_P_ACCZ_FLTD moved to Q_P_D_ACC_FLTD
1829
{ k_param_psc_key, 49425, AP_PARAM_FLOAT, "Q_P_D_ACC_SMAX" }, // Q_P_ACCZ_SMAX moved to Q_P_D_ACC_SMAX
1830
{ k_param_psc_key, 53521, AP_PARAM_FLOAT, "Q_P_D_ACC_PDMX" }, // Q_P_ACCZ_PDMX moved to Q_P_D_ACC_PDMX
1831
{ k_param_psc_key, 57617, AP_PARAM_FLOAT, "Q_P_D_ACC_D_FF" }, // Q_P_ACCZ_D_FF moved to Q_P_D_ACC_D_FF
1832
{ k_param_psc_key, 65809, AP_PARAM_INT8, "Q_P_D_ACC_NEF" }, // Q_P_ACCZ_NEF moved to Q_P_D_ACC_NEF
1833
{ k_param_psc_key, 61713, AP_PARAM_INT8, "Q_P_D_ACC_NTF" }, // Q_P_ACCZ_NTF moved to Q_P_D_ACC_NTF
1834
{ k_param_psc_key, 258449, AP_PARAM_FLOAT, "Q_P_NE_VEL_P" }, // Q_P_VELXY_P moved to Q_P_NE_VEL_P
1835
{ k_param_psc_key, 4497, AP_PARAM_FLOAT, "Q_P_NE_VEL_I" }, // Q_P_VELXY_I moved to Q_P_NE_VEL_I
1836
{ k_param_psc_key, 16785, AP_PARAM_FLOAT, "Q_P_NE_VEL_D" }, // Q_P_VELXY_D moved to Q_P_NE_VEL_D
1837
{ k_param_psc_key, 12689, AP_PARAM_FLOAT, "Q_P_NE_VEL_FLTE" },// Q_P_VELXY_FLTE moved to Q_P_NE_VEL_FLTE
1838
{ k_param_psc_key, 20881, AP_PARAM_FLOAT, "Q_P_NE_VEL_FLTD" },// Q_P_VELXY_FLTD moved to Q_P_NE_VEL_FLTD
1839
{ k_param_psc_key, 24977, AP_PARAM_FLOAT, "Q_P_NE_VEL_FF" }, // Q_P_VELXY_FF moved to Q_P_NE_VEL_FF
1840
};
1841
#else
1842
static const AP_Param::ConversionInfo conversion_info[] = {
1843
{ k_param_psc_key, 4035, AP_PARAM_FLOAT, "PSC_D_VEL_P" }, // PSC_VELZ_P moved to PSC_D_VEL_P
1844
{ k_param_psc_key, 67, AP_PARAM_FLOAT, "PSC_D_VEL_I" }, // PSC_VELZ_I moved to PSC_D_VEL_I
1845
{ k_param_psc_key, 259, AP_PARAM_FLOAT, "PSC_D_VEL_D" }, // PSC_VELZ_D moved to PSC_D_VEL_D
1846
{ k_param_psc_key, 195, AP_PARAM_FLOAT, "PSC_D_VEL_FLTE" }, // PSC_VELZ_FLTE moved to PSC_D_VEL_FLTE
1847
{ k_param_psc_key, 323, AP_PARAM_FLOAT, "PSC_D_VEL_FLTD" }, // PSC_VELZ_FLTD moved to PSC_D_VEL_FLTD
1848
{ k_param_psc_key, 387, AP_PARAM_FLOAT, "PSC_D_VEL_FF" }, // PSC_VELZ_FF moved to PSC_D_VEL_FF
1849
{ k_param_psc_key, 260, AP_PARAM_FLOAT, "PSC_D_ACC_FF" }, // PSC_ACCZ_FF moved to PSC_D_ACC_FF
1850
{ k_param_psc_key, 580, AP_PARAM_FLOAT, "PSC_D_ACC_FLTT" }, // PSC_ACCZ_FLTT moved to PSC_D_ACC_FLTT
1851
{ k_param_psc_key, 644, AP_PARAM_FLOAT, "PSC_D_ACC_FLTE" }, // PSC_ACCZ_FLTE moved to PSC_D_ACC_FLTE
1852
{ k_param_psc_key, 708, AP_PARAM_FLOAT, "PSC_D_ACC_FLTD" }, // PSC_ACCZ_FLTD moved to PSC_D_ACC_FLTD
1853
{ k_param_psc_key, 772, AP_PARAM_FLOAT, "PSC_D_ACC_SMAX" }, // PSC_ACCZ_SMAX moved to PSC_D_ACC_SMAX
1854
{ k_param_psc_key, 836, AP_PARAM_FLOAT, "PSC_D_ACC_PDMX" }, // PSC_ACCZ_PDMX moved to PSC_D_ACC_PDMX
1855
{ k_param_psc_key, 900, AP_PARAM_FLOAT, "PSC_D_ACC_D_FF" }, // PSC_ACCZ_D_FF moved to PSC_D_ACC_D_FF
1856
{ k_param_psc_key, 1028, AP_PARAM_INT8, "PSC_D_ACC_NEF" }, // PSC_ACCZ_NEF moved to PSC_D_ACC_NEF
1857
{ k_param_psc_key, 964, AP_PARAM_INT8, "PSC_D_ACC_NTF" }, // PSC_ACCZ_NTF moved to PSC_D_ACC_NTF
1858
{ k_param_psc_key, 4038, AP_PARAM_FLOAT, "PSC_NE_VEL_P" }, // PSC_VELXY_P moved to PSC_NE_VEL_P
1859
{ k_param_psc_key, 70, AP_PARAM_FLOAT, "PSC_NE_VEL_I" }, // PSC_VELXY_I moved to PSC_NE_VEL_I
1860
{ k_param_psc_key, 262, AP_PARAM_FLOAT, "PSC_NE_VEL_D" }, // PSC_VELXY_D moved to PSC_NE_VEL_D
1861
{ k_param_psc_key, 198, AP_PARAM_FLOAT, "PSC_NE_VEL_FLTE" },// PSC_VELXY_FLTE moved to PSC_NE_VEL_FLTE
1862
{ k_param_psc_key, 326, AP_PARAM_FLOAT, "PSC_NE_VEL_FLTD" },// PSC_VELXY_FLTD moved to PSC_NE_VEL_FLTD
1863
{ k_param_psc_key, 390, AP_PARAM_FLOAT, "PSC_NE_VEL_FF" }, // PSC_VELXY_FF moved to PSC_NE_VEL_FF
1864
};
1865
#endif
1866
AP_Param::convert_old_parameters(conversion_info, ARRAY_SIZE(conversion_info));
1867
1868
// parameters moved and scaled by 0.1
1869
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
1870
static const AP_Param::ConversionInfo conversion_info_01[] = {
1871
{ k_param_psc_key, 258321, AP_PARAM_FLOAT, "Q_P_D_ACC_P" }, // Q_P_ACCZ_P moved to Q_P_D_ACC_P
1872
{ k_param_psc_key, 4369, AP_PARAM_FLOAT, "Q_P_D_ACC_I" }, // Q_P_ACCZ_I moved to Q_P_D_ACC_I
1873
{ k_param_psc_key, 8465, AP_PARAM_FLOAT, "Q_P_D_ACC_D" }, // Q_P_ACCZ_D moved to Q_P_D_ACC_D
1874
};
1875
#else
1876
static const AP_Param::ConversionInfo conversion_info_01[] = {
1877
{ k_param_psc_key, 4036, AP_PARAM_FLOAT, "PSC_D_ACC_P" }, // PSC_ACCZ_P moved to PSC_D_ACC_P
1878
{ k_param_psc_key, 68, AP_PARAM_FLOAT, "PSC_D_ACC_I" }, // PSC_ACCZ_I moved to PSC_D_ACC_I
1879
{ k_param_psc_key, 132, AP_PARAM_FLOAT, "PSC_D_ACC_D" }, // PSC_ACCZ_D moved to PSC_D_ACC_D
1880
};
1881
#endif
1882
AP_Param::convert_old_parameters_scaled(conversion_info_01, ARRAY_SIZE(conversion_info_01), 0.1, 0);
1883
1884
// store PSC_D_ACC_P as flag that parameter conversion was completed
1885
_pid_accel_d_m.kP().save(true);
1886
1887
// parameters moved and scaled by 0.01
1888
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
1889
static const AP_Param::ConversionInfo conversion_info_001[] = {
1890
{ k_param_psc_key, 8401, AP_PARAM_FLOAT, "Q_P_D_VEL_IMAX" }, // Q_P_VELZ_IMAX moved to Q_P_D_VEL_IMAX
1891
{ k_param_psc_key, 8593, AP_PARAM_FLOAT, "Q_P_NE_VEL_IMAX" }, // Q_P_VELXY_IMAX moved to Q_P_NE_VEL_IMAX
1892
};
1893
#else
1894
static const AP_Param::ConversionInfo conversion_info_001[] = {
1895
{ k_param_psc_key, 131, AP_PARAM_FLOAT, "PSC_D_VEL_IMAX" }, // PSC_VELZ_IMAX moved to PSC_D_VEL_IMAX
1896
{ k_param_psc_key, 134, AP_PARAM_FLOAT, "PSC_NE_VEL_IMAX" }, // PSC_VELXY_IMAX moved to PSC_NE_VEL_IMAX
1897
};
1898
#endif
1899
AP_Param::convert_old_parameters_scaled(conversion_info_001, ARRAY_SIZE(conversion_info_001), 0.01, 0);
1900
1901
// parameters moved and scaled by 0.001
1902
// PSC_ACCZ_IMAX replaced by PSC_D_ACC_IMAX
1903
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
1904
static const AP_Param::ConversionInfo psc_d_acc_imax_info = { k_param_psc_key, 20753, AP_PARAM_FLOAT, "Q_P_D_ACC_IMAX" };
1905
#else
1906
static const AP_Param::ConversionInfo psc_d_acc_imax_info = { k_param_psc_key, 324, AP_PARAM_FLOAT, "PSC_D_ACC_IMAX" };
1907
#endif
1908
AP_Param::convert_old_parameter(&psc_d_acc_imax_info, 0.001f);
1909
}
1910
1911