CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

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

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AC_PrecLand/AC_PrecLand.cpp
Views: 1798
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_Companion.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, 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, 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, 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, 2.5f),
137
// @Param: STRICT
138
// @DisplayName: PrecLand strictness
139
// @Description: How strictly should the vehicle land on the target if target is lost
140
// @Values: 0: Land Vertically (Not strict), 1: Retry Landing(Normal Strictness), 2: Do not land (just Hover) (Very Strict)
141
AP_GROUPINFO("STRICT", 11, AC_PrecLand, _strict, 1),
142
143
// @Param: RET_MAX
144
// @DisplayName: PrecLand Maximum number of retires for a failed landing
145
// @Description: PrecLand Maximum number of retires for a failed landing. Set to zero to disable landing retry.
146
// @Range: 0 10
147
// @Increment: 1
148
AP_GROUPINFO("RET_MAX", 12, AC_PrecLand, _retry_max, 4),
149
150
// @Param: TIMEOUT
151
// @DisplayName: PrecLand retry timeout
152
// @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.
153
// @Range: 0 20
154
// @Units: s
155
AP_GROUPINFO("TIMEOUT", 13, AC_PrecLand, _retry_timeout_sec, 4),
156
157
// @Param: RET_BEHAVE
158
// @DisplayName: PrecLand retry behaviour
159
// @Description: Prec Land will do the action selected by this parameter if a retry to a landing is needed
160
// @Values: 0: Go to the last location where landing target was detected, 1: Go towards the approximate location of the detected landing target
161
AP_GROUPINFO("RET_BEHAVE", 14, AC_PrecLand, _retry_behave, 0),
162
163
// @Param: ALT_MIN
164
// @DisplayName: PrecLand minimum alt for retry
165
// @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.
166
// @Range: 0 5
167
// @Units: m
168
AP_GROUPINFO("ALT_MIN", 15, AC_PrecLand, _sensor_min_alt, 0.75),
169
170
// @Param: ALT_MAX
171
// @DisplayName: PrecLand maximum alt for retry
172
// @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.
173
// @Range: 0 50
174
// @Units: m
175
AP_GROUPINFO("ALT_MAX", 16, AC_PrecLand, _sensor_max_alt, 8),
176
177
// @Param: OPTIONS
178
// @DisplayName: Precision Landing Extra Options
179
// @Description: Precision Landing Extra Options
180
// @Bitmask: 0: Moving Landing Target, 1: Allow Precision Landing after manual reposition, 2: Maintain high speed in final descent
181
// @User: Advanced
182
AP_GROUPINFO("OPTIONS", 17, AC_PrecLand, _options, 0),
183
184
// @Param: ORIENT
185
// @DisplayName: Camera Orientation
186
// @Description: Orientation of camera/sensor on body
187
// @Values: 0:Forward, 4:Back, 25:Down
188
// @User: Advanced
189
// @RebootRequired: True
190
AP_GROUPINFO_FRAME("ORIENT", 18, AC_PrecLand, _orient, AC_PRECLAND_ORIENT_DEFAULT, AP_PARAM_FRAME_ROVER),
191
192
AP_GROUPEND
193
};
194
195
// Default constructor.
196
AC_PrecLand::AC_PrecLand()
197
{
198
if (_singleton != nullptr) {
199
AP_HAL::panic("AC_PrecLand must be singleton");
200
}
201
_singleton = this;
202
203
// set parameters to defaults
204
AP_Param::setup_object_defaults(this, var_info);
205
}
206
207
// perform any required initialisation of landing controllers
208
// update_rate_hz should be the rate at which the update method will be called in hz
209
void AC_PrecLand::init(uint16_t update_rate_hz)
210
{
211
// exit immediately if init has already been run
212
if (_backend != nullptr) {
213
return;
214
}
215
216
// init as target TARGET_NEVER_SEEN, we will update this later
217
_current_target_state = TargetState::TARGET_NEVER_SEEN;
218
219
// default health to false
220
_backend = nullptr;
221
_backend_state.healthy = false;
222
223
// create inertial history buffer
224
// constrain lag parameter to be within bounds
225
_lag.set(constrain_float(_lag, 0.02f, 0.25f)); // must match LAG parameter range at line 124
226
227
// calculate inertial buffer size from lag and minimum of main loop rate and update_rate_hz argument
228
const uint16_t inertial_buffer_size = MAX((uint16_t)roundf(_lag * update_rate_hz), 1);
229
230
// instantiate ring buffer to hold inertial history, return on failure so no backends are created
231
_inertial_history = NEW_NOTHROW ObjectArray<inertial_data_frame_s>(inertial_buffer_size);
232
if (_inertial_history == nullptr) {
233
return;
234
}
235
236
// instantiate backend based on type parameter
237
switch ((Type)(_type.get())) {
238
// no type defined
239
case Type::NONE:
240
default:
241
return;
242
// companion computer
243
#if AC_PRECLAND_COMPANION_ENABLED
244
case Type::COMPANION:
245
_backend = NEW_NOTHROW AC_PrecLand_Companion(*this, _backend_state);
246
break;
247
// IR Lock
248
#endif
249
#if AC_PRECLAND_IRLOCK_ENABLED
250
case Type::IRLOCK:
251
_backend = NEW_NOTHROW AC_PrecLand_IRLock(*this, _backend_state);
252
break;
253
#endif
254
#if AC_PRECLAND_SITL_GAZEBO_ENABLED
255
case Type::SITL_GAZEBO:
256
_backend = NEW_NOTHROW AC_PrecLand_SITL_Gazebo(*this, _backend_state);
257
break;
258
#endif
259
#if AC_PRECLAND_SITL_ENABLED
260
case Type::SITL:
261
_backend = NEW_NOTHROW AC_PrecLand_SITL(*this, _backend_state);
262
break;
263
#endif
264
}
265
266
// init backend
267
if (_backend != nullptr) {
268
_backend->init();
269
}
270
271
_approach_vector_body.x = 1;
272
_approach_vector_body.rotate(_orient);
273
}
274
275
// update - give chance to driver to get updates from sensor
276
void AC_PrecLand::update(float rangefinder_alt_cm, bool rangefinder_alt_valid)
277
{
278
// exit immediately if not enabled
279
if (_backend == nullptr || _inertial_history == nullptr) {
280
return;
281
}
282
283
// append current velocity and attitude correction into history buffer
284
struct inertial_data_frame_s inertial_data_newest;
285
const auto &_ahrs = AP::ahrs();
286
_ahrs.getCorrectedDeltaVelocityNED(inertial_data_newest.correctedVehicleDeltaVelocityNED, inertial_data_newest.dt);
287
inertial_data_newest.Tbn = _ahrs.get_rotation_body_to_ned();
288
Vector3f curr_vel;
289
nav_filter_status status;
290
if (!_ahrs.get_velocity_NED(curr_vel) || !_ahrs.get_filter_status(status)) {
291
inertial_data_newest.inertialNavVelocityValid = false;
292
} else {
293
inertial_data_newest.inertialNavVelocityValid = status.flags.horiz_vel;
294
}
295
curr_vel.z = -curr_vel.z; // NED to NEU
296
inertial_data_newest.inertialNavVelocity = curr_vel;
297
298
inertial_data_newest.time_usec = AP_HAL::micros64();
299
_inertial_history->push_force(inertial_data_newest);
300
301
const float rangefinder_alt_m = rangefinder_alt_cm*0.01f; //cm to meter
302
303
// update estimator of target position
304
if (_backend != nullptr && _enabled) {
305
_backend->update();
306
run_estimator(rangefinder_alt_m, rangefinder_alt_valid);
307
}
308
309
// check the status of the landing target location
310
check_target_status(rangefinder_alt_m, rangefinder_alt_valid);
311
312
#if HAL_LOGGING_ENABLED
313
const uint32_t now = AP_HAL::millis();
314
if (now - _last_log_ms > 40) { // 25Hz
315
_last_log_ms = now;
316
Write_Precland();
317
}
318
#endif
319
}
320
321
// check the status of the target
322
void AC_PrecLand::check_target_status(float rangefinder_alt_m, bool rangefinder_alt_valid)
323
{
324
if (target_acquired()) {
325
// target in sight
326
_current_target_state = TargetState::TARGET_FOUND;
327
// early return because we already know the status
328
return;
329
}
330
331
// target not in sight
332
if (_current_target_state == TargetState::TARGET_FOUND ||
333
_current_target_state == TargetState::TARGET_RECENTLY_LOST) {
334
// we had target in sight, but not any more, i.e we have lost the target
335
_current_target_state = TargetState::TARGET_RECENTLY_LOST;
336
} else {
337
// we never had the target in sight
338
_current_target_state = TargetState::TARGET_NEVER_SEEN;
339
}
340
341
// We definitely do not have the target in sight
342
// check if the precision landing sensor is supposed to be in range
343
// this needs a valid rangefinder to work
344
if (!check_if_sensor_in_range(rangefinder_alt_m, rangefinder_alt_valid)) {
345
// 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
346
_current_target_state = TargetState::TARGET_OUT_OF_RANGE;
347
return;
348
}
349
350
if (_current_target_state == TargetState::TARGET_RECENTLY_LOST) {
351
// check if it's nearby/found recently, else the status will be demoted to "TARGET_LOST"
352
Vector2f curr_pos;
353
if (AP::ahrs().get_relative_position_NE_origin(curr_pos)) {
354
const float dist_to_last_target_loc_xy = (curr_pos - Vector2f{_last_target_pos_rel_origin_NED.x, _last_target_pos_rel_origin_NED.y}).length();
355
const float dist_to_last_loc_xy = (curr_pos - Vector2f{_last_vehicle_pos_NED.x, _last_vehicle_pos_NED.y}).length();
356
if ((AP_HAL::millis() - _last_valid_target_ms) > LANDING_TARGET_LOST_TIMEOUT_MS) {
357
// the target has not been seen for a long time
358
// might as well consider it as "never seen"
359
_current_target_state = TargetState::TARGET_NEVER_SEEN;
360
return;
361
}
362
363
if ((dist_to_last_target_loc_xy > LANDING_TARGET_LOST_DIST_THRESH_M) || (dist_to_last_loc_xy > LANDING_TARGET_LOST_DIST_THRESH_M)) {
364
// the last known location of target is too far away
365
_current_target_state = TargetState::TARGET_NEVER_SEEN;
366
return;
367
}
368
}
369
}
370
}
371
372
// Check if the landing target is supposed to be in sight based on the height of the vehicle from the ground
373
// This needs a valid rangefinder to work, if the min/max parameters are non zero
374
bool AC_PrecLand::check_if_sensor_in_range(float rangefinder_alt_m, bool rangefinder_alt_valid) const
375
{
376
if (is_zero(_sensor_max_alt) && is_zero(_sensor_min_alt)) {
377
// no sensor limits have been specified, assume sensor is always in range
378
return true;
379
}
380
381
if (!rangefinder_alt_valid) {
382
// rangefinder isn't healthy. We might be at a very high altitude
383
return false;
384
}
385
386
if (rangefinder_alt_m > _sensor_max_alt && !is_zero(_sensor_max_alt)) {
387
// this prevents triggering a retry when we are too far away from the target
388
return false;
389
}
390
391
if (rangefinder_alt_m < _sensor_min_alt && !is_zero(_sensor_min_alt)) {
392
// this prevents triggering a retry when we are very close to the target
393
return false;
394
}
395
396
// target should be in range
397
return true;
398
}
399
400
bool AC_PrecLand::target_acquired()
401
{
402
if ((AP_HAL::millis()-_last_update_ms) > LANDING_TARGET_TIMEOUT_MS) {
403
if (_target_acquired) {
404
// just lost the landing target, inform the user. This message will only be sent once every time target is lost
405
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "PrecLand: Target Lost");
406
}
407
// not had a sensor update since a long time
408
// probably lost the target
409
_estimator_initialized = false;
410
_target_acquired = false;
411
}
412
return _target_acquired;
413
}
414
415
bool AC_PrecLand::get_target_position_cm(Vector2f& ret)
416
{
417
if (!target_acquired()) {
418
return false;
419
}
420
Vector2f curr_pos;
421
if (!AP::ahrs().get_relative_position_NE_origin(curr_pos)) {
422
return false;
423
}
424
ret.x = (_target_pos_rel_out_NE.x + curr_pos.x) * 100.0f; // m to cm
425
ret.y = (_target_pos_rel_out_NE.y + curr_pos.y) * 100.0f; // m to cm
426
return true;
427
}
428
429
void AC_PrecLand::get_target_position_measurement_cm(Vector3f& ret)
430
{
431
ret = _target_pos_rel_meas_NED*100.0f;
432
return;
433
}
434
435
bool AC_PrecLand::get_target_position_relative_cm(Vector2f& ret)
436
{
437
if (!target_acquired()) {
438
return false;
439
}
440
ret = _target_pos_rel_out_NE*100.0f;
441
return true;
442
}
443
444
bool AC_PrecLand::get_target_velocity_relative_cms(Vector2f& ret)
445
{
446
if (!target_acquired()) {
447
return false;
448
}
449
ret = _target_vel_rel_out_NE*100.0f;
450
return true;
451
}
452
453
// get the absolute velocity of the vehicle
454
void AC_PrecLand::get_target_velocity_cms(const Vector2f& vehicle_velocity_cms, Vector2f& target_vel_cms)
455
{
456
if (!(_options & PLND_OPTION_MOVING_TARGET)) {
457
// the target should not be moving
458
target_vel_cms.zero();
459
return;
460
}
461
if ((EstimatorType)_estimator_type.get() == EstimatorType::RAW_SENSOR) {
462
// We do not predict the velocity of the target in this case
463
// assume velocity to be zero
464
target_vel_cms.zero();
465
return;
466
}
467
Vector2f target_vel_rel_cms;
468
if (!get_target_velocity_relative_cms(target_vel_rel_cms)) {
469
// Don't know where the target is
470
// assume velocity to be zero
471
target_vel_cms.zero();
472
return;
473
}
474
// return the absolute velocity
475
target_vel_cms = target_vel_rel_cms + vehicle_velocity_cms;
476
}
477
478
// handle_msg - Process a LANDING_TARGET mavlink message
479
void AC_PrecLand::handle_msg(const mavlink_landing_target_t &packet, uint32_t timestamp_ms)
480
{
481
// run backend update
482
if (_backend != nullptr) {
483
_backend->handle_msg(packet, timestamp_ms);
484
}
485
}
486
487
//
488
// Private methods
489
//
490
491
void AC_PrecLand::run_estimator(float rangefinder_alt_m, bool rangefinder_alt_valid)
492
{
493
_inertial_data_delayed = (*_inertial_history)[0];
494
495
switch ((EstimatorType)_estimator_type.get()) {
496
case EstimatorType::RAW_SENSOR: {
497
// Return if there's any invalid velocity data
498
for (uint8_t i=0; i<_inertial_history->available(); i++) {
499
const struct inertial_data_frame_s *inertial_data = (*_inertial_history)[i];
500
if (!inertial_data->inertialNavVelocityValid) {
501
_target_acquired = false;
502
return;
503
}
504
}
505
506
// Predict
507
if (target_acquired()) {
508
_target_pos_rel_est_NE.x -= _inertial_data_delayed->inertialNavVelocity.x * _inertial_data_delayed->dt;
509
_target_pos_rel_est_NE.y -= _inertial_data_delayed->inertialNavVelocity.y * _inertial_data_delayed->dt;
510
_target_vel_rel_est_NE.x = -_inertial_data_delayed->inertialNavVelocity.x;
511
_target_vel_rel_est_NE.y = -_inertial_data_delayed->inertialNavVelocity.y;
512
}
513
514
// Update if a new Line-Of-Sight measurement is available
515
if (construct_pos_meas_using_rangefinder(rangefinder_alt_m, rangefinder_alt_valid)) {
516
if (!_estimator_initialized) {
517
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PrecLand: Target Found");
518
_estimator_initialized = true;
519
}
520
_target_pos_rel_est_NE.x = _target_pos_rel_meas_NED.x;
521
_target_pos_rel_est_NE.y = _target_pos_rel_meas_NED.y;
522
_target_vel_rel_est_NE.x = -_inertial_data_delayed->inertialNavVelocity.x;
523
_target_vel_rel_est_NE.y = -_inertial_data_delayed->inertialNavVelocity.y;
524
525
_last_update_ms = AP_HAL::millis();
526
_target_acquired = true;
527
}
528
529
// Output prediction
530
if (target_acquired()) {
531
run_output_prediction();
532
}
533
break;
534
}
535
case EstimatorType::KALMAN_FILTER: {
536
// Predict
537
if (target_acquired() || _estimator_initialized) {
538
const float& dt = _inertial_data_delayed->dt;
539
const Vector3f& vehicleDelVel = _inertial_data_delayed->correctedVehicleDeltaVelocityNED;
540
541
_ekf_x.predict(dt, -vehicleDelVel.x, _accel_noise*dt);
542
_ekf_y.predict(dt, -vehicleDelVel.y, _accel_noise*dt);
543
}
544
545
// Update if a new Line-Of-Sight measurement is available
546
if (construct_pos_meas_using_rangefinder(rangefinder_alt_m, rangefinder_alt_valid)) {
547
float xy_pos_var = sq(_target_pos_rel_meas_NED.z*(0.01f + 0.01f*AP::ahrs().get_gyro().length()) + 0.02f);
548
if (!_estimator_initialized) {
549
// Inform the user landing target has been found
550
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PrecLand: Target Found");
551
// start init of EKF. We will let the filter consume the data for a while before it available for consumption
552
// reset filter state
553
if (_inertial_data_delayed->inertialNavVelocityValid) {
554
_ekf_x.init(_target_pos_rel_meas_NED.x, xy_pos_var, -_inertial_data_delayed->inertialNavVelocity.x, sq(2.0f));
555
_ekf_y.init(_target_pos_rel_meas_NED.y, xy_pos_var, -_inertial_data_delayed->inertialNavVelocity.y, sq(2.0f));
556
} else {
557
_ekf_x.init(_target_pos_rel_meas_NED.x, xy_pos_var, 0.0f, sq(10.0f));
558
_ekf_y.init(_target_pos_rel_meas_NED.y, xy_pos_var, 0.0f, sq(10.0f));
559
}
560
_last_update_ms = AP_HAL::millis();
561
_estimator_init_ms = AP_HAL::millis();
562
// we have initialized the estimator but will not use the values for sometime so that EKF settles down
563
_estimator_initialized = true;
564
} else {
565
float NIS_x = _ekf_x.getPosNIS(_target_pos_rel_meas_NED.x, xy_pos_var);
566
float NIS_y = _ekf_y.getPosNIS(_target_pos_rel_meas_NED.y, xy_pos_var);
567
if (MAX(NIS_x, NIS_y) < 3.0f || _outlier_reject_count >= 3) {
568
_outlier_reject_count = 0;
569
_ekf_x.fusePos(_target_pos_rel_meas_NED.x, xy_pos_var);
570
_ekf_y.fusePos(_target_pos_rel_meas_NED.y, xy_pos_var);
571
_last_update_ms = AP_HAL::millis();
572
} else {
573
_outlier_reject_count++;
574
}
575
}
576
}
577
578
// check EKF was properly initialized when the sensor detected a landing target
579
check_ekf_init_timeout();
580
581
// Output prediction
582
if (target_acquired()) {
583
_target_pos_rel_est_NE.x = _ekf_x.getPos();
584
_target_pos_rel_est_NE.y = _ekf_y.getPos();
585
_target_vel_rel_est_NE.x = _ekf_x.getVel();
586
_target_vel_rel_est_NE.y = _ekf_y.getVel();
587
588
run_output_prediction();
589
}
590
break;
591
}
592
}
593
}
594
595
596
// check if EKF got the time to initialize when the landing target was first detected
597
// Expects sensor to update within EKF_INIT_SENSOR_MIN_UPDATE_MS milliseconds till EKF_INIT_TIME_MS milliseconds have passed
598
// after this period landing target estimates can be used by vehicle
599
void AC_PrecLand::check_ekf_init_timeout()
600
{
601
if (!target_acquired() && _estimator_initialized) {
602
// we have just got the target in sight
603
if (AP_HAL::millis()-_last_update_ms > EKF_INIT_SENSOR_MIN_UPDATE_MS) {
604
// we have lost the target, not enough readings to initialize the EKF
605
_estimator_initialized = false;
606
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "PrecLand: Init Failed");
607
} else if (AP_HAL::millis()-_estimator_init_ms > EKF_INIT_TIME_MS) {
608
// the target has been visible for a while, EKF should now have initialized to a good value
609
_target_acquired = true;
610
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PrecLand: Init Complete");
611
}
612
}
613
}
614
615
bool AC_PrecLand::retrieve_los_meas(Vector3f& target_vec_unit_body)
616
{
617
const uint32_t los_meas_time_ms = _backend->los_meas_time_ms();
618
if (los_meas_time_ms != _last_backend_los_meas_ms && _backend->get_los_body(target_vec_unit_body)) {
619
_last_backend_los_meas_ms = los_meas_time_ms;
620
if (!is_zero(_yaw_align)) {
621
// Apply sensor yaw alignment rotation
622
target_vec_unit_body.rotate_xy(radians(_yaw_align*0.01f));
623
}
624
625
626
// rotate vector based on sensor orientation to get correct body frame vector
627
if (_orient != ROTATION_PITCH_270) {
628
// by default, the vector is constructed downwards in body frame
629
// hence, we do not do any rotation if the orientation is downwards
630
// if it is some other orientation, we first bring the vector to forward
631
// and then we rotate it to desired orientation
632
// because the rotations are measured with respect to a vector pointing towards front in body frame
633
// for eg, if orientation is back, i.e., ROTATION_YAW_180,
634
// the vector is first brought to front and then rotation by YAW 180 to take it to the back of vehicle
635
target_vec_unit_body.rotate(ROTATION_PITCH_90); // bring vector to front
636
target_vec_unit_body.rotate(_orient); // rotate it to desired orientation
637
}
638
639
return true;
640
}
641
return false;
642
}
643
644
bool AC_PrecLand::construct_pos_meas_using_rangefinder(float rangefinder_alt_m, bool rangefinder_alt_valid)
645
{
646
Vector3f target_vec_unit_body;
647
if (retrieve_los_meas(target_vec_unit_body)) {
648
_inertial_data_delayed = (*_inertial_history)[0];
649
650
const bool target_vec_valid = target_vec_unit_body.projected(_approach_vector_body).dot(_approach_vector_body) > 0.0f;
651
const Vector3f target_vec_unit_ned = _inertial_data_delayed->Tbn * target_vec_unit_body;
652
const Vector3f approach_vector_NED = _inertial_data_delayed->Tbn * _approach_vector_body;
653
const bool alt_valid = (rangefinder_alt_valid && rangefinder_alt_m > 0.0f) || (_backend->distance_to_target() > 0.0f);
654
if (target_vec_valid && alt_valid) {
655
// distance to target and distance to target along approach vector
656
float dist_to_target, dist_to_target_along_av;
657
// figure out ned camera orientation w.r.t its offset
658
Vector3f cam_pos_ned;
659
if (!_cam_offset.get().is_zero()) {
660
// user has specifed offset for camera
661
// take its height into account while calculating distance
662
cam_pos_ned = _inertial_data_delayed->Tbn * _cam_offset;
663
}
664
if (_backend->distance_to_target() > 0.0f) {
665
// sensor has provided distance to landing target
666
dist_to_target = _backend->distance_to_target();
667
} else {
668
// sensor only knows the horizontal location of the landing target
669
// rely on rangefinder for the vertical target
670
dist_to_target_along_av = MAX(rangefinder_alt_m - cam_pos_ned.projected(approach_vector_NED).length(), 0.0f);
671
dist_to_target = dist_to_target_along_av / target_vec_unit_ned.projected(approach_vector_NED).length();
672
}
673
674
// Compute camera position relative to IMU
675
const Vector3f accel_pos_ned = _inertial_data_delayed->Tbn * AP::ins().get_imu_pos_offset(AP::ahrs().get_primary_accel_index());
676
const Vector3f cam_pos_ned_rel_imu = cam_pos_ned - accel_pos_ned;
677
678
// Compute target position relative to IMU
679
_target_pos_rel_meas_NED = (target_vec_unit_ned * dist_to_target) + cam_pos_ned_rel_imu;
680
681
// store the current relative down position so that if we need to retry landing, we know at this height landing target can be found
682
const AP_AHRS &_ahrs = AP::ahrs();
683
Vector3f pos_NED;
684
if (_ahrs.get_relative_position_NED_origin(pos_NED)) {
685
_last_target_pos_rel_origin_NED.z = pos_NED.z;
686
_last_vehicle_pos_NED = pos_NED;
687
}
688
return true;
689
}
690
}
691
return false;
692
}
693
694
void AC_PrecLand::run_output_prediction()
695
{
696
_target_pos_rel_out_NE = _target_pos_rel_est_NE;
697
_target_vel_rel_out_NE = _target_vel_rel_est_NE;
698
699
// Predict forward from delayed time horizon
700
for (uint8_t i=1; i<_inertial_history->available(); i++) {
701
const struct inertial_data_frame_s *inertial_data = (*_inertial_history)[i];
702
_target_vel_rel_out_NE.x -= inertial_data->correctedVehicleDeltaVelocityNED.x;
703
_target_vel_rel_out_NE.y -= inertial_data->correctedVehicleDeltaVelocityNED.y;
704
_target_pos_rel_out_NE.x += _target_vel_rel_out_NE.x * inertial_data->dt;
705
_target_pos_rel_out_NE.y += _target_vel_rel_out_NE.y * inertial_data->dt;
706
}
707
708
const AP_AHRS &_ahrs = AP::ahrs();
709
710
const Matrix3f& Tbn = (*_inertial_history)[_inertial_history->available()-1]->Tbn;
711
Vector3f accel_body_offset = AP::ins().get_imu_pos_offset(_ahrs.get_primary_accel_index());
712
713
// Apply position correction for CG offset from IMU
714
Vector3f imu_pos_ned = Tbn * accel_body_offset;
715
_target_pos_rel_out_NE.x += imu_pos_ned.x;
716
_target_pos_rel_out_NE.y += imu_pos_ned.y;
717
718
// Apply position correction for body-frame horizontal camera offset from CG, so that vehicle lands lens-to-target
719
Vector3f cam_pos_horizontal_ned = Tbn * Vector3f{_cam_offset.get().x, _cam_offset.get().y, 0};
720
_target_pos_rel_out_NE.x -= cam_pos_horizontal_ned.x;
721
_target_pos_rel_out_NE.y -= cam_pos_horizontal_ned.y;
722
723
// Apply velocity correction for IMU offset from CG
724
Vector3f vel_ned_rel_imu = Tbn * (_ahrs.get_gyro() % (-accel_body_offset));
725
_target_vel_rel_out_NE.x -= vel_ned_rel_imu.x;
726
_target_vel_rel_out_NE.y -= vel_ned_rel_imu.y;
727
728
// remember vehicle velocity
729
UNUSED_RESULT(_ahrs.get_velocity_NED(_last_veh_velocity_NED_ms));
730
731
// Apply land offset
732
Vector3f land_ofs_ned_m = _ahrs.get_rotation_body_to_ned() * Vector3f{_land_ofs_cm_x, _land_ofs_cm_y, 0} * 0.01f;
733
_target_pos_rel_out_NE.x += land_ofs_ned_m.x;
734
_target_pos_rel_out_NE.y += land_ofs_ned_m.y;
735
736
// store the landing target as a offset from current position. This is used in landing retry
737
Vector2f last_target_loc_rel_origin_2d;
738
get_target_position_cm(last_target_loc_rel_origin_2d);
739
_last_target_pos_rel_origin_NED.x = last_target_loc_rel_origin_2d.x * 0.01f;
740
_last_target_pos_rel_origin_NED.y = last_target_loc_rel_origin_2d.y * 0.01f;
741
742
// record the last time there was a target output
743
_last_valid_target_ms = AP_HAL::millis();
744
}
745
746
/*
747
get target location lat/lon. Note that altitude in returned
748
location is not reliable
749
*/
750
bool AC_PrecLand::get_target_location(Location &loc)
751
{
752
if (!target_acquired()) {
753
return false;
754
}
755
if (!AP::ahrs().get_origin(loc)) {
756
return false;
757
}
758
loc.offset(_last_target_pos_rel_origin_NED.x, _last_target_pos_rel_origin_NED.y);
759
loc.alt -= _last_target_pos_rel_origin_NED.z*100;
760
return true;
761
}
762
763
/*
764
get the absolute velocity of the target in m/s.
765
return false if we cannot estimate target velocity or if the target is not acquired
766
*/
767
bool AC_PrecLand::get_target_velocity(Vector2f& target_vel)
768
{
769
if (!(_options & PLND_OPTION_MOVING_TARGET)) {
770
// the target should not be moving
771
return false;
772
}
773
if ((EstimatorType)_estimator_type.get() == EstimatorType::RAW_SENSOR) {
774
return false;
775
}
776
Vector2f target_vel_rel_cms;
777
if (!get_target_velocity_relative_cms(target_vel_rel_cms)) {
778
return false;
779
}
780
// return the absolute velocity
781
target_vel = (target_vel_rel_cms*0.01) + _last_veh_velocity_NED_ms.xy();
782
return true;
783
}
784
785
#if HAL_LOGGING_ENABLED
786
// Write a precision landing entry
787
void AC_PrecLand::Write_Precland()
788
{
789
// exit immediately if not enabled
790
if (!enabled()) {
791
return;
792
}
793
794
Vector3f target_pos_meas;
795
Vector2f target_pos_rel;
796
Vector2f target_vel_rel;
797
get_target_position_relative_cm(target_pos_rel);
798
get_target_velocity_relative_cms(target_vel_rel);
799
get_target_position_measurement_cm(target_pos_meas);
800
801
const struct log_Precland pkt {
802
LOG_PACKET_HEADER_INIT(LOG_PRECLAND_MSG),
803
time_us : AP_HAL::micros64(),
804
healthy : healthy(),
805
target_acquired : target_acquired(),
806
pos_x : target_pos_rel.x,
807
pos_y : target_pos_rel.y,
808
vel_x : target_vel_rel.x,
809
vel_y : target_vel_rel.y,
810
meas_x : target_pos_meas.x,
811
meas_y : target_pos_meas.y,
812
meas_z : target_pos_meas.z,
813
last_meas : last_backend_los_meas_ms(),
814
ekf_outcount : ekf_outlier_count(),
815
estimator : (uint8_t)_estimator_type
816
};
817
AP::logger().WriteBlock(&pkt, sizeof(pkt));
818
}
819
#endif
820
821
// singleton instance
822
AC_PrecLand *AC_PrecLand::_singleton;
823
824
namespace AP {
825
826
AC_PrecLand *ac_precland()
827
{
828
return AC_PrecLand::get_singleton();
829
}
830
831
}
832
833
#endif // AC_PRECLAND_ENABLED
834
835