Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AC_PrecLand/AC_PrecLand.cpp
9460 views
1
#include "AC_PrecLand_config.h"
2
3
#if AC_PRECLAND_ENABLED
4
5
#include "AC_PrecLand.h"
6
#include <AP_HAL/AP_HAL.h>
7
#include <AP_AHRS/AP_AHRS.h>
8
9
#include "AC_PrecLand_Backend.h"
10
#include "AC_PrecLand_MAVLink.h"
11
#include "AC_PrecLand_IRLock.h"
12
#include "AC_PrecLand_SITL_Gazebo.h"
13
#include "AC_PrecLand_SITL.h"
14
#include <AP_Logger/AP_Logger.h>
15
#include <GCS_MAVLink/GCS.h>
16
#include <AP_Vehicle/AP_Vehicle_Type.h>
17
18
extern const AP_HAL::HAL& hal;
19
20
#if APM_BUILD_TYPE(APM_BUILD_Rover)
21
# define AC_PRECLAND_ORIENT_DEFAULT Rotation::ROTATION_NONE
22
#else
23
# define AC_PRECLAND_ORIENT_DEFAULT Rotation::ROTATION_PITCH_270
24
#endif
25
26
static const uint32_t EKF_INIT_TIME_MS = 2000; // EKF initialisation requires this many milliseconds of good sensor data
27
static const uint32_t EKF_INIT_SENSOR_MIN_UPDATE_MS = 500; // Sensor must update within this many ms during EKF init, else init will fail
28
static const uint32_t LANDING_TARGET_TIMEOUT_MS = 2000; // Sensor must update within this many ms, else prec landing will be switched off
29
static const uint32_t LANDING_TARGET_LOST_TIMEOUT_MS = 180000; // Target will be considered as "lost" if the last known location of the target is more than this many ms ago
30
static const float LANDING_TARGET_LOST_DIST_THRESH_M = 30; // If the last known location of the landing target is beyond this many meters, then we will consider it lost
31
32
const AP_Param::GroupInfo AC_PrecLand::var_info[] = {
33
// @Param: ENABLED
34
// @DisplayName: Precision Land enabled/disabled
35
// @Description: Precision Land enabled/disabled
36
// @Values: 0:Disabled, 1:Enabled
37
// @User: Advanced
38
AP_GROUPINFO_FLAGS("ENABLED", 0, AC_PrecLand, _enabled, 0, AP_PARAM_FLAG_ENABLE),
39
40
// @Param: TYPE
41
// @DisplayName: Precision Land Type
42
// @Description: Precision Land Type
43
// @Values: 0:None, 1:MAVLink, 2:IRLock, 3:SITL_Gazebo, 4:SITL
44
// @User: Advanced
45
AP_GROUPINFO("TYPE", 1, AC_PrecLand, _type, 0),
46
47
// @Param: YAW_ALIGN
48
// @DisplayName: Sensor yaw alignment
49
// @Description: Yaw angle from body x-axis to sensor x-axis.
50
// @Range: 0 36000
51
// @Increment: 10
52
// @User: Advanced
53
// @Units: cdeg
54
AP_GROUPINFO("YAW_ALIGN", 2, AC_PrecLand, _yaw_align_cd, 0),
55
56
// @Param: LAND_OFS_X
57
// @DisplayName: Land offset forward
58
// @Description: Desired landing position of the camera forward of the target in vehicle body frame
59
// @Range: -20 20
60
// @Increment: 1
61
// @User: Advanced
62
// @Units: cm
63
AP_GROUPINFO("LAND_OFS_X", 3, AC_PrecLand, _land_ofs_cm_x, 0),
64
65
// @Param: LAND_OFS_Y
66
// @DisplayName: Land offset right
67
// @Description: desired landing position of the camera right of the target in vehicle body frame
68
// @Range: -20 20
69
// @Increment: 1
70
// @User: Advanced
71
// @Units: cm
72
AP_GROUPINFO("LAND_OFS_Y", 4, AC_PrecLand, _land_ofs_cm_y, 0),
73
74
// @Param: EST_TYPE
75
// @DisplayName: Precision Land Estimator Type
76
// @Description: Specifies the estimation method to be used
77
// @Values: 0:RawSensor, 1:KalmanFilter
78
// @User: Advanced
79
AP_GROUPINFO("EST_TYPE", 5, AC_PrecLand, _estimator_type, 1),
80
81
// @Param: ACC_P_NSE
82
// @DisplayName: Kalman Filter Accelerometer Noise
83
// @Description: Kalman Filter Accelerometer Noise, higher values weight the input from the camera more, accels less
84
// @Range: 0.5 5
85
// @User: Advanced
86
AP_GROUPINFO("ACC_P_NSE", 6, AC_PrecLand, _accel_noise, 2.5f),
87
88
// @Param: CAM_POS_X
89
// @DisplayName: Camera X position offset
90
// @Description: X position of the camera in body frame. Positive X is forward of the origin.
91
// @Units: m
92
// @Range: -5 5
93
// @Increment: 0.01
94
// @User: Advanced
95
96
// @Param: CAM_POS_Y
97
// @DisplayName: Camera Y position offset
98
// @Description: Y position of the camera in body frame. Positive Y is to the right of the origin.
99
// @Units: m
100
// @Range: -5 5
101
// @Increment: 0.01
102
// @User: Advanced
103
104
// @Param: CAM_POS_Z
105
// @DisplayName: Camera Z position offset
106
// @Description: Z position of the camera in body frame. Positive Z is down from the origin.
107
// @Units: m
108
// @Range: -5 5
109
// @Increment: 0.01
110
// @User: Advanced
111
AP_GROUPINFO("CAM_POS", 7, AC_PrecLand, _cam_offset_m, 0.0f),
112
113
// @Param: BUS
114
// @DisplayName: Sensor Bus
115
// @Description: Precland sensor bus for I2C sensors.
116
// @Values: -1:DefaultBus,0:InternalI2C,1:ExternalI2C
117
// @User: Advanced
118
AP_GROUPINFO("BUS", 8, AC_PrecLand, _bus, -1),
119
120
// @Param: LAG
121
// @DisplayName: Precision Landing sensor lag
122
// @Description: Precision Landing sensor lag, to cope with variable landing_target latency
123
// @Range: 0.02 0.250
124
// @Increment: 1
125
// @Units: s
126
// @User: Advanced
127
// @RebootRequired: True
128
AP_GROUPINFO("LAG", 9, AC_PrecLand, _lag_s, 0.02f), // 20ms is the old default buffer size (8 frames @ 400hz/2.5ms)
129
130
// @Param: XY_DIST_MAX
131
// @DisplayName: Precision Landing maximum distance to target before descending
132
// @Description: The vehicle will not start descending if the landing target is detected and it is further than this many meters away. Set 0 to always descend.
133
// @Range: 0 10
134
// @Units: m
135
// @User: Advanced
136
AP_GROUPINFO("XY_DIST_MAX", 10, AC_PrecLand, _xy_max_dist_desc_m, 2.5f),
137
138
// @Param: STRICT
139
// @DisplayName: PrecLand strictness
140
// @Description: How strictly should the vehicle land on the target if target is lost
141
// @Values: 0: Land Vertically (Not strict), 1: Retry Landing(Normal Strictness), 2: Do not land (just Hover) (Very Strict)
142
AP_GROUPINFO("STRICT", 11, AC_PrecLand, _strict, 1),
143
144
// @Param: RET_MAX
145
// @DisplayName: PrecLand Maximum number of retires for a failed landing
146
// @Description: PrecLand Maximum number of retires for a failed landing. Set to zero to disable landing retry.
147
// @Range: 0 10
148
// @Increment: 1
149
AP_GROUPINFO("RET_MAX", 12, AC_PrecLand, _retry_max, 4),
150
151
// @Param: TIMEOUT
152
// @DisplayName: PrecLand retry timeout
153
// @Description: Time for which vehicle continues descend even if target is lost. After this time period, vehicle will attempt a landing retry depending on PLND_STRICT parameter.
154
// @Range: 0 20
155
// @Units: s
156
AP_GROUPINFO("TIMEOUT", 13, AC_PrecLand, _retry_timeout_s, 4),
157
158
// @Param: RET_BEHAVE
159
// @DisplayName: PrecLand retry behaviour
160
// @Description: Prec Land will do the action selected by this parameter if a retry to a landing is needed
161
// @Values: 0: Go to the last location where landing target was detected, 1: Go towards the approximate location of the detected landing target
162
AP_GROUPINFO("RET_BEHAVE", 14, AC_PrecLand, _retry_behave, 0),
163
164
// @Param: ALT_MIN
165
// @DisplayName: PrecLand minimum alt for retry
166
// @Description: Vehicle will continue landing vertically even if target is lost below this height. This needs a rangefinder to work. Set to zero to disable this.
167
// @Range: 0 5
168
// @Units: m
169
AP_GROUPINFO("ALT_MIN", 15, AC_PrecLand, _sensor_min_alt_m, 0.75),
170
171
// @Param: ALT_MAX
172
// @DisplayName: PrecLand maximum alt for retry
173
// @Description: Vehicle will continue landing vertically until this height if target is not found. Below this height if landing target is not found, landing retry/failsafe might be attempted. This needs a rangefinder to work. Set to zero to disable this.
174
// @Range: 0 50
175
// @Units: m
176
AP_GROUPINFO("ALT_MAX", 16, AC_PrecLand, _sensor_max_alt_m, 8),
177
178
// @Param: OPTIONS
179
// @DisplayName: Precision Landing Extra Options
180
// @Description: Precision Landing Extra Options
181
// @Bitmask: 0: Moving Landing Target, 1: Allow Precision Landing after manual reposition, 2: Maintain high speed in final descent
182
// @User: Advanced
183
AP_GROUPINFO("OPTIONS", 17, AC_PrecLand, _options, 0),
184
185
// @Param{Rover,Copter}: ORIENT
186
// @DisplayName: Camera Orientation
187
// @Description: Orientation of camera/sensor on body
188
// @Values: 0:Forward, 4:Back, 25:Down
189
// @User: Advanced
190
// @RebootRequired: True
191
AP_GROUPINFO_FRAME("ORIENT", 18, AC_PrecLand, _orient, AC_PRECLAND_ORIENT_DEFAULT, AP_PARAM_FRAME_ROVER | AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_TRICOPTER | AP_PARAM_FRAME_HELI),
192
193
AP_GROUPEND
194
};
195
196
// Default constructor.
197
AC_PrecLand::AC_PrecLand()
198
{
199
if (_singleton != nullptr) {
200
AP_HAL::panic("AC_PrecLand must be singleton");
201
}
202
_singleton = this;
203
204
// set parameters to defaults
205
AP_Param::setup_object_defaults(this, var_info);
206
}
207
208
// perform any required initialisation of landing controllers
209
// update_rate_hz should be the rate at which the update method will be called in hz
210
void AC_PrecLand::init(uint16_t update_rate_hz)
211
{
212
// exit immediately if init has already been run
213
if (_backend != nullptr) {
214
return;
215
}
216
217
// init as target TARGET_NEVER_SEEN, we will update this later
218
_current_target_state = TargetState::TARGET_NEVER_SEEN;
219
220
// default health to false
221
_backend = nullptr;
222
_backend_state.healthy = false;
223
224
// create inertial history buffer
225
// constrain lag parameter to be within bounds
226
_lag_s.set(constrain_float(_lag_s, 0.02f, 0.25f)); // must match LAG parameter range at line 124
227
228
// calculate inertial buffer size from lag and minimum of main loop rate and update_rate_hz argument
229
const uint16_t inertial_buffer_size = MAX((uint16_t)roundf(_lag_s * update_rate_hz), 1);
230
231
// instantiate ring buffer to hold inertial history, return on failure so no backends are created
232
_inertial_history = NEW_NOTHROW ObjectArray<inertial_data_frame_s>(inertial_buffer_size);
233
if (_inertial_history == nullptr) {
234
return;
235
}
236
237
// instantiate backend based on type parameter
238
switch ((Type)(_type.get())) {
239
// no type defined
240
case Type::NONE:
241
default:
242
return;
243
// companion computer
244
#if AC_PRECLAND_MAVLINK_ENABLED
245
case Type::MAVLINK:
246
_backend = NEW_NOTHROW AC_PrecLand_MAVLink(*this, _backend_state);
247
break;
248
// IR Lock
249
#endif
250
#if AC_PRECLAND_IRLOCK_ENABLED
251
case Type::IRLOCK:
252
_backend = NEW_NOTHROW AC_PrecLand_IRLock(*this, _backend_state);
253
break;
254
#endif
255
#if AC_PRECLAND_SITL_GAZEBO_ENABLED
256
case Type::SITL_GAZEBO:
257
_backend = NEW_NOTHROW AC_PrecLand_SITL_Gazebo(*this, _backend_state);
258
break;
259
#endif
260
#if AC_PRECLAND_SITL_ENABLED
261
case Type::SITL:
262
_backend = NEW_NOTHROW AC_PrecLand_SITL(*this, _backend_state);
263
break;
264
#endif
265
}
266
267
// init backend
268
if (_backend != nullptr) {
269
_backend->init();
270
}
271
272
_approach_vector_body.x = 1;
273
_approach_vector_body.rotate(_orient);
274
}
275
276
// update - give chance to driver to get updates from sensor
277
void AC_PrecLand::update(float rangefinder_alt_cm, bool rangefinder_alt_valid)
278
{
279
// exit immediately if not enabled
280
if (_backend == nullptr || _inertial_history == nullptr) {
281
return;
282
}
283
284
// append current velocity and attitude correction into history buffer
285
struct inertial_data_frame_s inertial_data_newest;
286
const auto &_ahrs = AP::ahrs();
287
_ahrs.getCorrectedDeltaVelocityNED(inertial_data_newest.correctedVehicleDeltaVelocityNED, inertial_data_newest.dt);
288
inertial_data_newest.Tbn = _ahrs.get_rotation_body_to_ned();
289
Vector3f curr_vel;
290
nav_filter_status status;
291
if (!_ahrs.get_velocity_NED(curr_vel) || !_ahrs.get_filter_status(status)) {
292
inertial_data_newest.inertialNavVelocityValid = false;
293
} else {
294
inertial_data_newest.inertialNavVelocityValid = status.flags.horiz_vel;
295
}
296
curr_vel.z = -curr_vel.z; // NED to NEU
297
inertial_data_newest.inertialNavVelocity = curr_vel;
298
299
inertial_data_newest.time_usec = AP_HAL::micros64();
300
_inertial_history->push_force(inertial_data_newest);
301
302
const float rangefinder_alt_m = rangefinder_alt_cm*0.01f; //cm to meter
303
304
// update estimator of target position
305
if (_backend != nullptr && _enabled) {
306
_backend->update();
307
run_estimator(rangefinder_alt_m, rangefinder_alt_valid);
308
}
309
310
// check the status of the landing target location
311
check_target_status(rangefinder_alt_m, rangefinder_alt_valid);
312
313
#if HAL_LOGGING_ENABLED
314
const uint32_t now = AP_HAL::millis();
315
if (now - _last_log_ms > 40) { // 25Hz
316
_last_log_ms = now;
317
Write_Precland();
318
}
319
#endif
320
}
321
322
// check the status of the target
323
void AC_PrecLand::check_target_status(float rangefinder_alt_m, bool rangefinder_alt_valid)
324
{
325
if (target_acquired()) {
326
// target in sight
327
_current_target_state = TargetState::TARGET_FOUND;
328
// early return because we already know the status
329
return;
330
}
331
332
// target not in sight
333
if (_current_target_state == TargetState::TARGET_FOUND ||
334
_current_target_state == TargetState::TARGET_RECENTLY_LOST) {
335
// we had target in sight, but not any more, i.e we have lost the target
336
_current_target_state = TargetState::TARGET_RECENTLY_LOST;
337
} else {
338
// we never had the target in sight
339
_current_target_state = TargetState::TARGET_NEVER_SEEN;
340
}
341
342
// We definitely do not have the target in sight
343
// check if the precision landing sensor is supposed to be in range
344
// this needs a valid rangefinder to work
345
if (!check_if_sensor_in_range(rangefinder_alt_m, rangefinder_alt_valid)) {
346
// Target is not in range (vehicle is either too high or too low). Vehicle will not be attempting any sort of landing retries during this period
347
_current_target_state = TargetState::TARGET_OUT_OF_RANGE;
348
return;
349
}
350
351
if (_current_target_state == TargetState::TARGET_RECENTLY_LOST) {
352
// check if it's nearby/found recently, else the status will be demoted to "TARGET_LOST"
353
Vector2p curr_pos_ne_m;
354
if (AP::ahrs().get_relative_position_NE_origin(curr_pos_ne_m)) {
355
const float dist_to_last_target_loc_xy = (curr_pos_ne_m - _last_target_pos_rel_origin_ned_m.xy()).length();
356
const float dist_to_last_loc_ne_m = (curr_pos_ne_m - _last_vehicle_pos_ned_m.xy()).length();
357
if ((AP_HAL::millis() - _last_valid_target_ms) > LANDING_TARGET_LOST_TIMEOUT_MS) {
358
// the target has not been seen for a long time
359
// might as well consider it as "never seen"
360
_current_target_state = TargetState::TARGET_NEVER_SEEN;
361
return;
362
}
363
364
if ((dist_to_last_target_loc_xy > LANDING_TARGET_LOST_DIST_THRESH_M) || (dist_to_last_loc_ne_m > LANDING_TARGET_LOST_DIST_THRESH_M)) {
365
// the last known location of target is too far away
366
_current_target_state = TargetState::TARGET_NEVER_SEEN;
367
return;
368
}
369
}
370
}
371
}
372
373
// Check if the landing target is supposed to be in sight based on the height of the vehicle from the ground
374
// This needs a valid rangefinder to work, if the min/max parameters are non zero
375
bool AC_PrecLand::check_if_sensor_in_range(float rangefinder_alt_m, bool rangefinder_alt_valid) const
376
{
377
if (is_zero(_sensor_max_alt_m) && is_zero(_sensor_min_alt_m)) {
378
// no sensor limits have been specified, assume sensor is always in range
379
return true;
380
}
381
382
if (!rangefinder_alt_valid) {
383
// rangefinder isn't healthy. We might be at a very high altitude
384
return false;
385
}
386
387
if (rangefinder_alt_m > _sensor_max_alt_m && !is_zero(_sensor_max_alt_m)) {
388
// this prevents triggering a retry when we are too far away from the target
389
return false;
390
}
391
392
if (rangefinder_alt_m < _sensor_min_alt_m && !is_zero(_sensor_min_alt_m)) {
393
// this prevents triggering a retry when we are very close to the target
394
return false;
395
}
396
397
// target should be in range
398
return true;
399
}
400
401
// returns true when the landing target has been detected
402
bool AC_PrecLand::target_acquired()
403
{
404
if ((AP_HAL::millis()-_last_update_ms) > LANDING_TARGET_TIMEOUT_MS) {
405
if (_target_acquired) {
406
// just lost the landing target, inform the user. This message will only be sent once every time target is lost
407
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "PrecLand: Target Lost");
408
}
409
// not had a sensor update since a long time
410
// probably lost the target
411
_estimator_initialized = false;
412
_target_acquired = false;
413
}
414
return _target_acquired;
415
}
416
417
// returns target position relative to the EKF origin
418
bool AC_PrecLand::get_target_position_m(Vector2p& ret)
419
{
420
if (!target_acquired()) {
421
return false;
422
}
423
Vector2p curr_pos_ne_m;
424
if (!AP::ahrs().get_relative_position_NE_origin(curr_pos_ne_m)) {
425
return false;
426
}
427
ret.x = (_target_pos_rel_out_ne_m.x + curr_pos_ne_m.x);
428
ret.y = (_target_pos_rel_out_ne_m.y + curr_pos_ne_m.y);
429
return true;
430
}
431
432
// returns target relative position as 3D vector
433
void AC_PrecLand::get_target_position_measurement_NED_m(Vector3f& ret)
434
{
435
ret = _target_pos_rel_meas_ned_m;
436
return;
437
}
438
439
// returns target position relative to vehicle
440
bool AC_PrecLand::get_target_position_relative_NE_m(Vector2f& ret)
441
{
442
if (!target_acquired()) {
443
return false;
444
}
445
ret = _target_pos_rel_out_ne_m;
446
return true;
447
}
448
449
// returns target velocity relative to vehicle
450
bool AC_PrecLand::get_target_velocity_relative_NE_ms(Vector2f& ret)
451
{
452
if (!target_acquired()) {
453
return false;
454
}
455
ret = _target_vel_rel_out_ne_ms;
456
return true;
457
}
458
459
// get the absolute velocity of the vehicle
460
void AC_PrecLand::get_target_velocity_ms(const Vector2f& vehicle_velocity_ne_ms, Vector2f& target_vel_ne_ms)
461
{
462
if (!(_options & PLND_OPTION_MOVING_TARGET)) {
463
// the target should not be moving
464
target_vel_ne_ms.zero();
465
return;
466
}
467
if ((EstimatorType)_estimator_type.get() == EstimatorType::RAW_SENSOR) {
468
// We do not predict the velocity of the target in this case
469
// assume velocity to be zero
470
target_vel_ne_ms.zero();
471
return;
472
}
473
Vector2f target_vel_rel_ne_ms;
474
if (!get_target_velocity_relative_NE_ms(target_vel_rel_ne_ms)) {
475
// Don't know where the target is
476
// assume velocity to be zero
477
target_vel_ne_ms.zero();
478
return;
479
}
480
// return the absolute velocity
481
target_vel_ne_ms = target_vel_rel_ne_ms + vehicle_velocity_ne_ms;
482
}
483
484
// handle_msg - Process a LANDING_TARGET mavlink message
485
void AC_PrecLand::handle_msg(const mavlink_landing_target_t &packet, uint32_t timestamp_ms)
486
{
487
// run backend update
488
if (_backend != nullptr) {
489
_backend->handle_msg(packet, timestamp_ms);
490
}
491
}
492
493
//
494
// Private methods
495
//
496
497
// run target position estimator
498
void AC_PrecLand::run_estimator(float rangefinder_alt_m, bool rangefinder_alt_valid)
499
{
500
_inertial_data_delayed = (*_inertial_history)[0];
501
502
switch ((EstimatorType)_estimator_type.get()) {
503
case EstimatorType::RAW_SENSOR: {
504
// Return if there's any invalid velocity data
505
for (uint8_t i=0; i<_inertial_history->available(); i++) {
506
const struct inertial_data_frame_s *inertial_data = (*_inertial_history)[i];
507
if (!inertial_data->inertialNavVelocityValid) {
508
_target_acquired = false;
509
return;
510
}
511
}
512
513
// Predict
514
if (target_acquired()) {
515
_target_pos_rel_est_ne_m.x -= _inertial_data_delayed->inertialNavVelocity.x * _inertial_data_delayed->dt;
516
_target_pos_rel_est_ne_m.y -= _inertial_data_delayed->inertialNavVelocity.y * _inertial_data_delayed->dt;
517
_target_vel_rel_est_ne_ms.x = -_inertial_data_delayed->inertialNavVelocity.x;
518
_target_vel_rel_est_ne_ms.y = -_inertial_data_delayed->inertialNavVelocity.y;
519
}
520
521
// Update if a new Line-Of-Sight measurement is available
522
if (construct_pos_meas_using_rangefinder(rangefinder_alt_m, rangefinder_alt_valid)) {
523
if (!_estimator_initialized) {
524
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PrecLand: Target Found");
525
_estimator_initialized = true;
526
}
527
_target_pos_rel_est_ne_m.x = _target_pos_rel_meas_ned_m.x;
528
_target_pos_rel_est_ne_m.y = _target_pos_rel_meas_ned_m.y;
529
_target_vel_rel_est_ne_ms.x = -_inertial_data_delayed->inertialNavVelocity.x;
530
_target_vel_rel_est_ne_ms.y = -_inertial_data_delayed->inertialNavVelocity.y;
531
532
_last_update_ms = AP_HAL::millis();
533
_target_acquired = true;
534
}
535
536
// Output prediction
537
if (target_acquired()) {
538
run_output_prediction();
539
}
540
break;
541
}
542
case EstimatorType::KALMAN_FILTER: {
543
// Predict
544
if (target_acquired() || _estimator_initialized) {
545
const float& dt = _inertial_data_delayed->dt;
546
const Vector3f& vehicleDelVel = _inertial_data_delayed->correctedVehicleDeltaVelocityNED;
547
548
_ekf_x.predict(dt, -vehicleDelVel.x, _accel_noise*dt);
549
_ekf_y.predict(dt, -vehicleDelVel.y, _accel_noise*dt);
550
}
551
552
// Update if a new Line-Of-Sight measurement is available
553
if (construct_pos_meas_using_rangefinder(rangefinder_alt_m, rangefinder_alt_valid)) {
554
float xy_pos_var = sq(_target_pos_rel_meas_ned_m.z*(0.01f + 0.01f*AP::ahrs().get_gyro().length()) + 0.02f);
555
if (!_estimator_initialized) {
556
// Inform the user landing target has been found
557
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PrecLand: Target Found");
558
// start init of EKF. We will let the filter consume the data for a while before it available for consumption
559
// reset filter state
560
if (_inertial_data_delayed->inertialNavVelocityValid) {
561
_ekf_x.init(_target_pos_rel_meas_ned_m.x, xy_pos_var, -_inertial_data_delayed->inertialNavVelocity.x, sq(2.0f));
562
_ekf_y.init(_target_pos_rel_meas_ned_m.y, xy_pos_var, -_inertial_data_delayed->inertialNavVelocity.y, sq(2.0f));
563
} else {
564
_ekf_x.init(_target_pos_rel_meas_ned_m.x, xy_pos_var, 0.0f, sq(10.0f));
565
_ekf_y.init(_target_pos_rel_meas_ned_m.y, xy_pos_var, 0.0f, sq(10.0f));
566
}
567
_last_update_ms = AP_HAL::millis();
568
_estimator_init_ms = AP_HAL::millis();
569
// we have initialized the estimator but will not use the values for sometime so that EKF settles down
570
_estimator_initialized = true;
571
} else {
572
float NIS_x = _ekf_x.getPosNIS(_target_pos_rel_meas_ned_m.x, xy_pos_var);
573
float NIS_y = _ekf_y.getPosNIS(_target_pos_rel_meas_ned_m.y, xy_pos_var);
574
if (MAX(NIS_x, NIS_y) < 3.0f || _outlier_reject_count >= 3) {
575
_outlier_reject_count = 0;
576
_ekf_x.fusePos(_target_pos_rel_meas_ned_m.x, xy_pos_var);
577
_ekf_y.fusePos(_target_pos_rel_meas_ned_m.y, xy_pos_var);
578
_last_update_ms = AP_HAL::millis();
579
} else {
580
_outlier_reject_count++;
581
}
582
}
583
}
584
585
// check EKF was properly initialized when the sensor detected a landing target
586
check_ekf_init_timeout();
587
588
// Output prediction
589
if (target_acquired()) {
590
_target_pos_rel_est_ne_m.x = _ekf_x.getPos();
591
_target_pos_rel_est_ne_m.y = _ekf_y.getPos();
592
_target_vel_rel_est_ne_ms.x = _ekf_x.getVel();
593
_target_vel_rel_est_ne_ms.y = _ekf_y.getVel();
594
595
run_output_prediction();
596
}
597
break;
598
}
599
}
600
}
601
602
603
// check if EKF got the time to initialize when the landing target was first detected
604
// Expects sensor to update within EKF_INIT_SENSOR_MIN_UPDATE_MS milliseconds till EKF_INIT_TIME_MS milliseconds have passed
605
// after this period landing target estimates can be used by vehicle
606
void AC_PrecLand::check_ekf_init_timeout()
607
{
608
if (!target_acquired() && _estimator_initialized) {
609
// we have just got the target in sight
610
if (AP_HAL::millis()-_last_update_ms > EKF_INIT_SENSOR_MIN_UPDATE_MS) {
611
// we have lost the target, not enough readings to initialize the EKF
612
_estimator_initialized = false;
613
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "PrecLand: Init Failed");
614
} else if (AP_HAL::millis()-_estimator_init_ms > EKF_INIT_TIME_MS) {
615
// the target has been visible for a while, EKF should now have initialized to a good value
616
_target_acquired = true;
617
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PrecLand: Init Complete");
618
}
619
}
620
}
621
622
// get 3D vector from vehicle to target and frame. returns true on success, false on failure
623
bool AC_PrecLand::retrieve_los_meas(Vector3f& target_vec_unit, VectorFrame& frame)
624
{
625
const uint32_t los_meas_time_ms = _backend->los_meas_time_ms();
626
if ((los_meas_time_ms != _last_backend_los_meas_ms) && _backend->get_los_meas(target_vec_unit, frame)) {
627
_last_backend_los_meas_ms = los_meas_time_ms;
628
if (!is_zero(_yaw_align_cd)) {
629
// Apply sensor yaw alignment rotation
630
target_vec_unit.rotate_xy(cd_to_rad(_yaw_align_cd));
631
}
632
633
// rotate vector based on sensor orientation to get correct body frame vector
634
if (_orient != ROTATION_PITCH_270) {
635
// by default, the vector is constructed downwards in body frame
636
// hence, we do not do any rotation if the orientation is downwards
637
// if it is some other orientation, we first bring the vector to forward
638
// and then we rotate it to desired orientation
639
// because the rotations are measured with respect to a vector pointing towards front in body frame
640
// for eg, if orientation is back, i.e., ROTATION_YAW_180,
641
// the vector is first brought to front and then rotation by YAW 180 to take it to the back of vehicle
642
target_vec_unit.rotate(ROTATION_PITCH_90); // bring vector to front
643
target_vec_unit.rotate(_orient); // rotate it to desired orientation
644
}
645
646
return true;
647
}
648
return false;
649
}
650
651
// If a new measurement was retrieved, sets _target_pos_rel_meas_ned_m and returns true
652
bool AC_PrecLand::construct_pos_meas_using_rangefinder(float rangefinder_alt_m, bool rangefinder_alt_valid)
653
{
654
Vector3f target_vec_unit;
655
VectorFrame target_vec_frame;
656
if (retrieve_los_meas(target_vec_unit, target_vec_frame)) {
657
_inertial_data_delayed = (*_inertial_history)[0];
658
659
// sanity check vector is pointing in the right direction
660
const bool target_vec_valid = target_vec_unit.projected(_approach_vector_body).dot(_approach_vector_body) > 0.0f;
661
662
// calculate 3D vector to target in NED frame
663
Vector3f target_vec_unit_ned;
664
switch (target_vec_frame) {
665
case VectorFrame::BODY_FRD:
666
// convert to NED
667
target_vec_unit_ned = _inertial_data_delayed->Tbn * target_vec_unit;
668
break;
669
case VectorFrame::LOCAL_FRD:
670
// rotate vector using delayed yaw
671
float roll_rad, pitch_rad, yaw_rad;
672
_inertial_data_delayed->Tbn.to_euler(&roll_rad, &pitch_rad, &yaw_rad);
673
target_vec_unit_ned = target_vec_unit;
674
target_vec_unit_ned.rotate_xy(-yaw_rad);
675
break;
676
}
677
678
const Vector3f approach_vector_NED_m = _inertial_data_delayed->Tbn * _approach_vector_body;
679
const bool alt_valid = (rangefinder_alt_valid && rangefinder_alt_m > 0.0f) || (_backend->distance_to_target() > 0.0f);
680
if (target_vec_valid && alt_valid) {
681
// distance to target and distance to target along approach vector
682
float dist_to_target_m, dist_to_target_along_av_m;
683
// figure out ned camera orientation w.r.t its offset
684
Vector3f cam_pos_ned_m;
685
if (!_cam_offset_m.get().is_zero()) {
686
// user has specifed offset for camera
687
// take its height into account while calculating distance
688
cam_pos_ned_m = _inertial_data_delayed->Tbn * _cam_offset_m;
689
}
690
if (_backend->distance_to_target() > 0.0f) {
691
// sensor has provided distance to landing target
692
dist_to_target_m = _backend->distance_to_target();
693
} else {
694
// sensor only knows the horizontal location of the landing target
695
// rely on rangefinder for the vertical target
696
dist_to_target_along_av_m = MAX(rangefinder_alt_m - cam_pos_ned_m.projected(approach_vector_NED_m).length(), 0.0f);
697
dist_to_target_m = dist_to_target_along_av_m / target_vec_unit_ned.projected(approach_vector_NED_m).length();
698
}
699
700
// Compute camera position relative to IMU
701
const Vector3f accel_pos_ned_m = _inertial_data_delayed->Tbn * AP::ins().get_imu_pos_offset(AP::ahrs().get_primary_accel_index());
702
const Vector3f cam_pos_ned_rel_imu_ned_m = cam_pos_ned_m - accel_pos_ned_m;
703
704
// Compute target position relative to IMU
705
_target_pos_rel_meas_ned_m = (target_vec_unit_ned * dist_to_target_m) + cam_pos_ned_rel_imu_ned_m;
706
707
// store the current relative down position so that if we need to retry landing, we know at this height landing target can be found
708
const AP_AHRS &_ahrs = AP::ahrs();
709
Vector3p pos_NED;
710
if (_ahrs.get_relative_position_NED_origin(pos_NED)) {
711
_last_target_pos_rel_origin_ned_m.z = pos_NED.z;
712
_last_vehicle_pos_ned_m = pos_NED;
713
}
714
return true;
715
}
716
}
717
return false;
718
}
719
720
// calculate target's position and velocity relative to the vehicle (used as input to position controller)
721
// results are stored in_target_pos_rel_out_NE, _target_vel_rel_out_ne_ms
722
void AC_PrecLand::run_output_prediction()
723
{
724
_target_pos_rel_out_ne_m = _target_pos_rel_est_ne_m;
725
_target_vel_rel_out_ne_ms = _target_vel_rel_est_ne_ms;
726
727
// Predict forward from delayed time horizon
728
for (uint8_t i=1; i<_inertial_history->available(); i++) {
729
const struct inertial_data_frame_s *inertial_data = (*_inertial_history)[i];
730
_target_vel_rel_out_ne_ms.x -= inertial_data->correctedVehicleDeltaVelocityNED.x;
731
_target_vel_rel_out_ne_ms.y -= inertial_data->correctedVehicleDeltaVelocityNED.y;
732
_target_pos_rel_out_ne_m.x += _target_vel_rel_out_ne_ms.x * inertial_data->dt;
733
_target_pos_rel_out_ne_m.y += _target_vel_rel_out_ne_ms.y * inertial_data->dt;
734
}
735
736
const AP_AHRS &_ahrs = AP::ahrs();
737
738
const Matrix3f& Tbn = (*_inertial_history)[_inertial_history->available()-1]->Tbn;
739
Vector3f accel_body_offset = AP::ins().get_imu_pos_offset(_ahrs.get_primary_accel_index());
740
741
// Apply position correction for CG offset from IMU
742
Vector3f imu_pos_ned = Tbn * accel_body_offset;
743
_target_pos_rel_out_ne_m.x += imu_pos_ned.x;
744
_target_pos_rel_out_ne_m.y += imu_pos_ned.y;
745
746
// Apply position correction for body-frame horizontal camera offset from CG, so that vehicle lands lens-to-target
747
Vector3f cam_pos_horizontal_ned = Tbn * Vector3f{_cam_offset_m.get().x, _cam_offset_m.get().y, 0};
748
_target_pos_rel_out_ne_m.x -= cam_pos_horizontal_ned.x;
749
_target_pos_rel_out_ne_m.y -= cam_pos_horizontal_ned.y;
750
751
// Apply velocity correction for IMU offset from CG
752
Vector3f vel_ned_rel_imu = Tbn * (_ahrs.get_gyro() % (-accel_body_offset));
753
_target_vel_rel_out_ne_ms.x -= vel_ned_rel_imu.x;
754
_target_vel_rel_out_ne_ms.y -= vel_ned_rel_imu.y;
755
756
// remember vehicle velocity
757
UNUSED_RESULT(_ahrs.get_velocity_NED(_last_veh_velocity_NED_ms));
758
759
// Apply land offset
760
Vector3f land_ofs_ned_m = _ahrs.get_rotation_body_to_ned() * Vector3f{_land_ofs_cm_x, _land_ofs_cm_y, 0} * 0.01f;
761
_target_pos_rel_out_ne_m.x += land_ofs_ned_m.x;
762
_target_pos_rel_out_ne_m.y += land_ofs_ned_m.y;
763
764
// store the landing target as a offset from current position. This is used in landing retry
765
Vector2p last_target_loc_rel_origin_ne_m;
766
get_target_position_m(last_target_loc_rel_origin_ne_m);
767
_last_target_pos_rel_origin_ned_m.x = last_target_loc_rel_origin_ne_m.x;
768
_last_target_pos_rel_origin_ned_m.y = last_target_loc_rel_origin_ne_m.y;
769
770
// record the last time there was a target output
771
_last_valid_target_ms = AP_HAL::millis();
772
}
773
774
/*
775
get target location lat/lon. Note that altitude in returned
776
location is not reliable
777
*/
778
bool AC_PrecLand::get_target_location(Location &loc)
779
{
780
if (!target_acquired()) {
781
return false;
782
}
783
if (!AP::ahrs().get_origin(loc)) {
784
return false;
785
}
786
loc.offset(_last_target_pos_rel_origin_ned_m.x, _last_target_pos_rel_origin_ned_m.y);
787
loc.offset_up_m(-_last_target_pos_rel_origin_ned_m.z);
788
return true;
789
}
790
791
/*
792
get the absolute velocity of the target in m/s.
793
return false if we cannot estimate target velocity or if the target is not acquired
794
*/
795
bool AC_PrecLand::get_target_velocity(Vector2f& target_vel)
796
{
797
if (!(_options & PLND_OPTION_MOVING_TARGET)) {
798
// the target should not be moving
799
return false;
800
}
801
if ((EstimatorType)_estimator_type.get() == EstimatorType::RAW_SENSOR) {
802
return false;
803
}
804
Vector2f target_vel_rel_ne_ms;
805
if (!get_target_velocity_relative_NE_ms(target_vel_rel_ne_ms)) {
806
return false;
807
}
808
// return the absolute velocity
809
target_vel = (target_vel_rel_ne_ms) + _last_veh_velocity_NED_ms.xy();
810
return true;
811
}
812
813
#if HAL_LOGGING_ENABLED
814
// Write a precision landing entry
815
void AC_PrecLand::Write_Precland()
816
{
817
// exit immediately if not enabled
818
if (!enabled()) {
819
return;
820
}
821
822
Vector2f target_pos_rel_ne_m;
823
Vector2f target_vel_rel_ne_ms;
824
Vector3f target_pos_meas_ned_m;
825
get_target_position_relative_NE_m(target_pos_rel_ne_m);
826
get_target_velocity_relative_NE_ms(target_vel_rel_ne_ms);
827
get_target_position_measurement_NED_m(target_pos_meas_ned_m);
828
829
const struct log_Precland pkt {
830
LOG_PACKET_HEADER_INIT(LOG_PRECLAND_MSG),
831
time_us : AP_HAL::micros64(),
832
healthy : healthy(),
833
target_acquired : target_acquired(),
834
pos_x : target_pos_rel_ne_m.x,
835
pos_y : target_pos_rel_ne_m.y,
836
vel_x : target_vel_rel_ne_ms.x,
837
vel_y : target_vel_rel_ne_ms.y,
838
meas_x : target_pos_meas_ned_m.x,
839
meas_y : target_pos_meas_ned_m.y,
840
meas_z : target_pos_meas_ned_m.z,
841
last_meas : last_backend_los_meas_ms(),
842
ekf_outcount : ekf_outlier_count(),
843
estimator : (uint8_t)_estimator_type
844
};
845
AP::logger().WriteBlock(&pkt, sizeof(pkt));
846
}
847
#endif
848
849
// singleton instance
850
AC_PrecLand *AC_PrecLand::_singleton;
851
852
namespace AP {
853
854
AC_PrecLand *ac_precland()
855
{
856
return AC_PrecLand::get_singleton();
857
}
858
859
}
860
861
#endif // AC_PRECLAND_ENABLED
862
863