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/ArduPlane/altitude.cpp
Views: 1798
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
16
#include "Plane.h"
17
18
/*
19
altitude handling routines. These cope with both barometric control
20
and terrain following control
21
*/
22
23
/*
24
adjust altitude target depending on mode
25
*/
26
void Plane::adjust_altitude_target()
27
{
28
control_mode->update_target_altitude();
29
}
30
31
void Plane::check_home_alt_change(void)
32
{
33
int32_t home_alt_cm = ahrs.get_home().alt;
34
if (home_alt_cm != auto_state.last_home_alt_cm && hal.util->get_soft_armed()) {
35
// cope with home altitude changing
36
const int32_t alt_change_cm = home_alt_cm - auto_state.last_home_alt_cm;
37
if (next_WP_loc.terrain_alt) {
38
/*
39
next_WP_loc for terrain alt WP are quite strange. They
40
have terrain_alt=1, but also have relative_alt=0 and
41
have been calculated to be relative to home. We need to
42
adjust for the change in home alt
43
*/
44
next_WP_loc.alt += alt_change_cm;
45
}
46
// reset TECS to force the field elevation estimate to reset
47
TECS_controller.offset_altitude(alt_change_cm * 0.01f);
48
}
49
auto_state.last_home_alt_cm = home_alt_cm;
50
}
51
52
/*
53
setup for a gradual glide slope to the next waypoint, if appropriate
54
*/
55
void Plane::setup_glide_slope(void)
56
{
57
// establish the distance we are travelling to the next waypoint,
58
// for calculating out rate of change of altitude
59
auto_state.wp_distance = current_loc.get_distance(next_WP_loc);
60
auto_state.wp_proportion = current_loc.line_path_proportion(prev_WP_loc, next_WP_loc);
61
TECS_controller.set_path_proportion(auto_state.wp_proportion);
62
update_flight_stage();
63
64
/*
65
work out if we will gradually change altitude, or try to get to
66
the new altitude as quickly as possible.
67
*/
68
switch (control_mode->mode_number()) {
69
case Mode::Number::RTL:
70
case Mode::Number::AVOID_ADSB:
71
case Mode::Number::GUIDED:
72
/* glide down slowly if above target altitude, but ascend more
73
rapidly if below it. See
74
https://github.com/ArduPilot/ardupilot/issues/39
75
*/
76
if (above_location_current(next_WP_loc)) {
77
set_offset_altitude_location(prev_WP_loc, next_WP_loc);
78
} else {
79
reset_offset_altitude();
80
}
81
break;
82
83
case Mode::Number::AUTO:
84
85
//climb without doing glide slope if option is enabled
86
if (!above_location_current(next_WP_loc) && plane.flight_option_enabled(FlightOptions::IMMEDIATE_CLIMB_IN_AUTO)) {
87
reset_offset_altitude();
88
break;
89
}
90
91
// we only do glide slide handling in AUTO when above 20m or
92
// when descending. The 20 meter threshold is arbitrary, and
93
// is basically to prevent situations where we try to slowly
94
// gain height at low altitudes, potentially hitting
95
// obstacles.
96
if (adjusted_relative_altitude_cm() > 2000 || above_location_current(next_WP_loc)) {
97
set_offset_altitude_location(prev_WP_loc, next_WP_loc);
98
} else {
99
reset_offset_altitude();
100
}
101
break;
102
default:
103
reset_offset_altitude();
104
break;
105
}
106
}
107
108
/*
109
return RTL altitude as AMSL cm
110
*/
111
int32_t Plane::get_RTL_altitude_cm() const
112
{
113
if (g.RTL_altitude < 0) {
114
return current_loc.alt;
115
}
116
return g.RTL_altitude*100 + home.alt;
117
}
118
119
/*
120
return relative altitude in meters (relative to terrain, if available,
121
or home otherwise)
122
*/
123
float Plane::relative_ground_altitude(bool use_rangefinder_if_available, bool use_terrain_if_available)
124
{
125
#if AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED
126
float height_AGL;
127
// use external HAGL if available
128
if (get_external_HAGL(height_AGL)) {
129
return height_AGL;
130
}
131
#endif // AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED
132
133
#if AP_RANGEFINDER_ENABLED
134
if (use_rangefinder_if_available && rangefinder_state.in_range) {
135
return rangefinder_state.height_estimate;
136
}
137
#endif
138
139
#if HAL_QUADPLANE_ENABLED && AP_RANGEFINDER_ENABLED
140
if (use_rangefinder_if_available && quadplane.in_vtol_land_final() &&
141
rangefinder.status_orient(rangefinder_orientation()) == RangeFinder::Status::OutOfRangeLow) {
142
// a special case for quadplane landing when rangefinder goes
143
// below minimum. Consider our height above ground to be zero
144
return 0;
145
}
146
#endif
147
148
#if AP_TERRAIN_AVAILABLE
149
float altitude;
150
if (use_terrain_if_available &&
151
terrain.status() == AP_Terrain::TerrainStatusOK &&
152
terrain.height_above_terrain(altitude, true)) {
153
return altitude;
154
}
155
#endif
156
157
#if HAL_QUADPLANE_ENABLED
158
if (quadplane.in_vtol_land_descent() &&
159
!quadplane.landing_with_fixed_wing_spiral_approach()) {
160
// when doing a VTOL landing we can use the waypoint height as
161
// ground height. We can't do this if using the
162
// LAND_FW_APPROACH as that uses the wp height as the approach
163
// height
164
return height_above_target();
165
}
166
#endif
167
168
return relative_altitude;
169
}
170
171
// Helper for above method using terrain if the vehicle is currently terrain following
172
float Plane::relative_ground_altitude(bool use_rangefinder_if_available)
173
{
174
#if AP_TERRAIN_AVAILABLE
175
return relative_ground_altitude(use_rangefinder_if_available, target_altitude.terrain_following);
176
#else
177
return relative_ground_altitude(use_rangefinder_if_available, false);
178
#endif
179
}
180
181
182
/*
183
set the target altitude to the current altitude. This is used when
184
setting up for altitude hold, such as when releasing elevator in
185
CRUISE mode.
186
*/
187
void Plane::set_target_altitude_current(void)
188
{
189
// record altitude above sea level at the current time as our
190
// target altitude
191
target_altitude.amsl_cm = current_loc.alt;
192
193
// reset any glide slope offset
194
reset_offset_altitude();
195
196
#if AP_TERRAIN_AVAILABLE
197
// also record the terrain altitude if possible
198
float terrain_altitude;
199
if (terrain_enabled_in_current_mode() && terrain.height_above_terrain(terrain_altitude, true) && !terrain_disabled()) {
200
target_altitude.terrain_following = true;
201
target_altitude.terrain_alt_cm = terrain_altitude*100;
202
} else {
203
// if terrain following is disabled, or we don't know our
204
// terrain altitude when we set the altitude then don't
205
// terrain follow
206
target_altitude.terrain_following = false;
207
}
208
#endif
209
}
210
211
/*
212
set the target altitude to the current altitude, with ALT_OFFSET adjustment
213
*/
214
void Plane::set_target_altitude_current_adjusted(void)
215
{
216
set_target_altitude_current();
217
218
// use adjusted_altitude_cm() to take account of ALTITUDE_OFFSET
219
target_altitude.amsl_cm = adjusted_altitude_cm();
220
}
221
222
/*
223
set target altitude based on a location structure
224
*/
225
void Plane::set_target_altitude_location(const Location &loc)
226
{
227
target_altitude.amsl_cm = loc.alt;
228
if (loc.relative_alt) {
229
target_altitude.amsl_cm += home.alt;
230
}
231
#if AP_TERRAIN_AVAILABLE
232
if (target_altitude.terrain_following_pending) {
233
/* we didn't get terrain data to init when we started on this
234
target, retry
235
*/
236
setup_terrain_target_alt(next_WP_loc);
237
}
238
/*
239
if this location has the terrain_alt flag set and we know the
240
terrain altitude of our current location then treat it as a
241
terrain altitude
242
*/
243
float height;
244
if (loc.terrain_alt && terrain.height_above_terrain(height, true)) {
245
target_altitude.terrain_following = true;
246
target_altitude.terrain_alt_cm = loc.alt;
247
if (!loc.relative_alt) {
248
// it has home added, remove it
249
target_altitude.terrain_alt_cm -= home.alt;
250
}
251
} else {
252
target_altitude.terrain_following = false;
253
}
254
#endif
255
}
256
257
/*
258
return relative to home target altitude in centimeters. Used for
259
altitude control libraries
260
*/
261
int32_t Plane::relative_target_altitude_cm(void)
262
{
263
#if AP_TERRAIN_AVAILABLE
264
float relative_home_height;
265
if (target_altitude.terrain_following &&
266
terrain.height_relative_home_equivalent(target_altitude.terrain_alt_cm*0.01f,
267
relative_home_height, true)) {
268
// add lookahead adjustment the target altitude
269
target_altitude.lookahead = lookahead_adjustment();
270
relative_home_height += target_altitude.lookahead;
271
272
#if AP_RANGEFINDER_ENABLED
273
// correct for rangefinder data
274
relative_home_height += rangefinder_correction();
275
#endif
276
277
// we are following terrain, and have terrain data for the
278
// current location. Use it.
279
return relative_home_height*100;
280
}
281
#endif
282
int32_t relative_alt = target_altitude.amsl_cm - home.alt;
283
relative_alt += mission_alt_offset()*100;
284
#if AP_RANGEFINDER_ENABLED
285
relative_alt += rangefinder_correction() * 100;
286
#endif
287
return relative_alt;
288
}
289
290
/*
291
change the current target altitude by an amount in centimeters. Used
292
to cope with changes due to elevator in CRUISE or FBWB
293
*/
294
void Plane::change_target_altitude(int32_t change_cm)
295
{
296
target_altitude.amsl_cm += change_cm;
297
#if AP_TERRAIN_AVAILABLE
298
if (target_altitude.terrain_following && !terrain_disabled()) {
299
target_altitude.terrain_alt_cm += change_cm;
300
}
301
#endif
302
}
303
/*
304
change target altitude by a proportion of the target altitude offset
305
(difference in height to next WP from previous WP). proportion
306
should be between 0 and 1.
307
308
When proportion is zero we have reached the destination. When
309
proportion is 1 we are at the starting waypoint.
310
311
Note that target_altitude is setup initially based on the
312
destination waypoint
313
*/
314
void Plane::set_target_altitude_proportion(const Location &loc, float proportion)
315
{
316
set_target_altitude_location(loc);
317
proportion = constrain_float(proportion, 0.0f, 1.0f);
318
change_target_altitude(-target_altitude.offset_cm*proportion);
319
//rebuild the glide slope if we are above it and supposed to be climbing
320
if(g.glide_slope_threshold > 0) {
321
if(target_altitude.offset_cm > 0 && calc_altitude_error_cm() < -100 * g.glide_slope_threshold) {
322
set_target_altitude_location(loc);
323
set_offset_altitude_location(current_loc, loc);
324
change_target_altitude(-target_altitude.offset_cm*proportion);
325
//adjust the new target offset altitude to reflect that we are partially already done
326
if(proportion > 0.0f)
327
target_altitude.offset_cm = ((float)target_altitude.offset_cm)/proportion;
328
}
329
}
330
}
331
332
/*
333
constrain target altitude to be between two locations. Used to
334
ensure we stay within two waypoints in altitude
335
*/
336
void Plane::constrain_target_altitude_location(const Location &loc1, const Location &loc2)
337
{
338
if (loc1.alt > loc2.alt) {
339
target_altitude.amsl_cm = constrain_int32(target_altitude.amsl_cm, loc2.alt, loc1.alt);
340
} else {
341
target_altitude.amsl_cm = constrain_int32(target_altitude.amsl_cm, loc1.alt, loc2.alt);
342
}
343
}
344
345
/*
346
return error between target altitude and current altitude
347
*/
348
int32_t Plane::calc_altitude_error_cm(void)
349
{
350
#if AP_TERRAIN_AVAILABLE
351
float terrain_height;
352
if (target_altitude.terrain_following &&
353
terrain.height_above_terrain(terrain_height, true)) {
354
return target_altitude.lookahead*100 + target_altitude.terrain_alt_cm - (terrain_height*100);
355
}
356
#endif
357
return target_altitude.amsl_cm - adjusted_altitude_cm();
358
}
359
360
/*
361
check for cruise_alt_floor and fence min/max altitude
362
*/
363
void Plane::check_fbwb_altitude(void)
364
{
365
float max_alt_cm = 0.0;
366
float min_alt_cm = 0.0;
367
bool should_check_max = false;
368
bool should_check_min = false;
369
370
#if AP_FENCE_ENABLED
371
// taking fence max and min altitude (with margin)
372
const uint8_t enabled_fences = plane.fence.get_enabled_fences();
373
if ((enabled_fences & AC_FENCE_TYPE_ALT_MIN) != 0) {
374
min_alt_cm = plane.fence.get_safe_alt_min()*100.0;
375
should_check_min = true;
376
}
377
if ((enabled_fences & AC_FENCE_TYPE_ALT_MAX) != 0) {
378
max_alt_cm = plane.fence.get_safe_alt_max()*100.0;
379
should_check_max = true;
380
}
381
#endif
382
383
if (g.cruise_alt_floor > 0) {
384
// FBWB min altitude exists
385
min_alt_cm = MAX(min_alt_cm, plane.g.cruise_alt_floor*100.0);
386
should_check_min = true;
387
}
388
389
if (!should_check_min && !should_check_max) {
390
return;
391
}
392
393
//check if terrain following (min and max)
394
#if AP_TERRAIN_AVAILABLE
395
if (target_altitude.terrain_following) {
396
// set our target terrain height to be at least the min set
397
if (should_check_max) {
398
target_altitude.terrain_alt_cm = MIN(target_altitude.terrain_alt_cm, max_alt_cm);
399
}
400
if (should_check_min) {
401
target_altitude.terrain_alt_cm = MAX(target_altitude.terrain_alt_cm, min_alt_cm);
402
}
403
return;
404
}
405
#endif
406
407
if (should_check_max) {
408
target_altitude.amsl_cm = MIN(target_altitude.amsl_cm, home.alt + max_alt_cm);
409
}
410
if (should_check_min) {
411
target_altitude.amsl_cm = MAX(target_altitude.amsl_cm, home.alt + min_alt_cm);
412
}
413
}
414
415
/*
416
reset the altitude offset used for glide slopes
417
*/
418
void Plane::reset_offset_altitude(void)
419
{
420
target_altitude.offset_cm = 0;
421
}
422
423
424
/*
425
reset the altitude offset used for glide slopes, based on difference
426
between altitude at a destination and a specified start altitude. If
427
destination is above the starting altitude then the result is
428
positive.
429
*/
430
void Plane::set_offset_altitude_location(const Location &start_loc, const Location &destination_loc)
431
{
432
target_altitude.offset_cm = destination_loc.alt - start_loc.alt;
433
434
#if AP_TERRAIN_AVAILABLE
435
/*
436
if this location has the terrain_alt flag set and we know the
437
terrain altitude of our current location then treat it as a
438
terrain altitude
439
*/
440
float height;
441
if (destination_loc.terrain_alt &&
442
target_altitude.terrain_following &&
443
terrain.height_above_terrain(height, true)) {
444
target_altitude.offset_cm = target_altitude.terrain_alt_cm - (height * 100);
445
}
446
#endif
447
448
if (flight_stage != AP_FixedWing::FlightStage::LAND) {
449
// if we are within GLIDE_SLOPE_MIN meters of the target altitude
450
// then reset the offset to not use a glide slope. This allows for
451
// more accurate flight of missions where the aircraft may lose or
452
// gain a bit of altitude near waypoint turn points due to local
453
// terrain changes
454
if (g.glide_slope_min <= 0 ||
455
labs(target_altitude.offset_cm)*0.01f < g.glide_slope_min) {
456
target_altitude.offset_cm = 0;
457
}
458
}
459
}
460
461
/*
462
return true if current_loc is above loc. Used for glide slope
463
calculations.
464
465
"above" is simple if we are not terrain following, as it just means
466
the pressure altitude of one is above the other.
467
468
When in terrain following mode "above" means the over-the-terrain
469
current altitude is above the over-the-terrain alt of loc. It is
470
quite possible for current_loc to be "above" loc when it is at a
471
lower pressure altitude, if current_loc is in a low part of the
472
terrain
473
*/
474
bool Plane::above_location_current(const Location &loc)
475
{
476
#if AP_TERRAIN_AVAILABLE
477
float terrain_alt;
478
if (loc.terrain_alt &&
479
terrain.height_above_terrain(terrain_alt, true)) {
480
float loc_alt = loc.alt*0.01f;
481
if (!loc.relative_alt) {
482
loc_alt -= home.alt*0.01f;
483
}
484
return terrain_alt > loc_alt;
485
}
486
#endif
487
488
float loc_alt_cm = loc.alt;
489
if (loc.relative_alt) {
490
loc_alt_cm += home.alt;
491
}
492
return current_loc.alt > loc_alt_cm;
493
}
494
495
/*
496
modify a destination to be setup for terrain following if
497
TERRAIN_FOLLOW is enabled
498
*/
499
void Plane::setup_terrain_target_alt(Location &loc)
500
{
501
#if AP_TERRAIN_AVAILABLE
502
if (terrain_enabled_in_current_mode()) {
503
if (!loc.change_alt_frame(Location::AltFrame::ABOVE_TERRAIN)) {
504
target_altitude.terrain_following_pending = true;
505
return;
506
}
507
}
508
target_altitude.terrain_following_pending = false;
509
#endif
510
}
511
512
/*
513
return current_loc.alt adjusted for ALT_OFFSET
514
This is useful during long flights to account for barometer changes
515
from the GCS, or to adjust the flying height of a long mission
516
*/
517
int32_t Plane::adjusted_altitude_cm(void)
518
{
519
return current_loc.alt - (mission_alt_offset()*100);
520
}
521
522
/*
523
return home-relative altitude adjusted for ALT_OFFSET. This is useful
524
during long flights to account for barometer changes from the GCS,
525
or to adjust the flying height of a long mission.
526
*/
527
int32_t Plane::adjusted_relative_altitude_cm(void)
528
{
529
return (relative_altitude - mission_alt_offset())*100;
530
}
531
532
533
/*
534
return the mission altitude offset. This raises or lowers all
535
mission items. It is primarily set using the ALT_OFFSET parameter,
536
but can also be adjusted by the rangefinder landing code for a
537
NAV_LAND command if we have aborted a steep landing
538
*/
539
float Plane::mission_alt_offset(void)
540
{
541
float ret = g.alt_offset;
542
if (control_mode == &mode_auto &&
543
(flight_stage == AP_FixedWing::FlightStage::LAND || auto_state.wp_is_land_approach)) {
544
// when landing after an aborted landing due to too high glide
545
// slope we use an offset from the last landing attempt
546
ret += landing.alt_offset;
547
}
548
return ret;
549
}
550
551
/*
552
return the height in meters above the next_WP_loc altitude
553
*/
554
float Plane::height_above_target(void)
555
{
556
float target_alt = next_WP_loc.alt*0.01;
557
if (!next_WP_loc.relative_alt) {
558
target_alt -= ahrs.get_home().alt*0.01f;
559
}
560
561
#if AP_TERRAIN_AVAILABLE
562
// also record the terrain altitude if possible
563
float terrain_altitude;
564
if (next_WP_loc.terrain_alt &&
565
terrain.height_above_terrain(terrain_altitude, true)) {
566
return terrain_altitude - target_alt;
567
}
568
#endif
569
570
return (adjusted_altitude_cm()*0.01f - ahrs.get_home().alt*0.01f) - target_alt;
571
}
572
573
/*
574
work out target altitude adjustment from terrain lookahead
575
*/
576
float Plane::lookahead_adjustment(void)
577
{
578
#if AP_TERRAIN_AVAILABLE
579
int32_t bearing_cd;
580
int16_t distance;
581
// work out distance and bearing to target
582
if (control_mode == &mode_fbwb) {
583
// there is no target waypoint in FBWB, so use yaw as an approximation
584
bearing_cd = ahrs.yaw_sensor;
585
distance = g.terrain_lookahead;
586
} else if (!reached_loiter_target()) {
587
bearing_cd = nav_controller->target_bearing_cd();
588
distance = constrain_float(auto_state.wp_distance, 0, g.terrain_lookahead);
589
} else {
590
// no lookahead when loitering
591
bearing_cd = 0;
592
distance = 0;
593
}
594
if (distance <= 0) {
595
// no lookahead
596
return 0;
597
}
598
599
600
float groundspeed = ahrs.groundspeed();
601
if (groundspeed < 1) {
602
// we're not moving
603
return 0;
604
}
605
// we need to know the climb ratio. We use 50% of the maximum
606
// climb rate so we are not constantly at 100% throttle and to
607
// give a bit more margin on terrain
608
float climb_ratio = 0.5f * TECS_controller.get_max_climbrate() / groundspeed;
609
610
if (climb_ratio <= 0) {
611
// lookahead makes no sense for negative climb rates
612
return 0;
613
}
614
615
// ask the terrain code for the lookahead altitude change
616
float lookahead = terrain.lookahead(bearing_cd*0.01f, distance, climb_ratio);
617
618
if (target_altitude.offset_cm < 0) {
619
// we are heading down to the waypoint, so we don't need to
620
// climb as much
621
lookahead += target_altitude.offset_cm*0.01f;
622
}
623
624
// constrain lookahead to a reasonable limit
625
return constrain_float(lookahead, 0, 1000.0f);
626
#else
627
return 0;
628
#endif
629
}
630
631
632
#if AP_RANGEFINDER_ENABLED
633
/*
634
correct target altitude using rangefinder data. Returns offset in
635
meters to correct target altitude. A positive number means we need
636
to ask the speed/height controller to fly higher
637
*/
638
float Plane::rangefinder_correction(void)
639
{
640
if (millis() - rangefinder_state.last_correction_time_ms > 5000) {
641
// we haven't had any rangefinder data for 5s - don't use it
642
return 0;
643
}
644
645
// for now we only support the rangefinder for landing
646
bool using_rangefinder = (g.rangefinder_landing && flight_stage == AP_FixedWing::FlightStage::LAND);
647
if (!using_rangefinder) {
648
return 0;
649
}
650
651
return rangefinder_state.correction;
652
}
653
654
/*
655
correct rangefinder data for terrain height difference between
656
NAV_LAND point and current location
657
*/
658
void Plane::rangefinder_terrain_correction(float &height)
659
{
660
#if AP_TERRAIN_AVAILABLE
661
if (!g.rangefinder_landing ||
662
flight_stage != AP_FixedWing::FlightStage::LAND ||
663
!terrain_enabled_in_current_mode()) {
664
return;
665
}
666
float terrain_amsl1, terrain_amsl2;
667
if (!terrain.height_amsl(current_loc, terrain_amsl1) ||
668
!terrain.height_amsl(next_WP_loc, terrain_amsl2)) {
669
return;
670
}
671
float correction = (terrain_amsl1 - terrain_amsl2);
672
height += correction;
673
auto_state.terrain_correction = correction;
674
#endif
675
}
676
677
/*
678
update the offset between rangefinder height and terrain height
679
*/
680
void Plane::rangefinder_height_update(void)
681
{
682
const auto orientation = rangefinder_orientation();
683
bool range_ok = rangefinder.status_orient(orientation) == RangeFinder::Status::Good;
684
float distance = rangefinder.distance_orient(orientation);
685
float corrected_distance = distance;
686
687
/*
688
correct distance for attitude
689
*/
690
if (range_ok) {
691
// correct the range for attitude
692
const auto &dcm = ahrs.get_rotation_body_to_ned();
693
694
Vector3f v{corrected_distance, 0, 0};
695
v.rotate(orientation);
696
v = dcm * v;
697
698
if (!is_positive(v.z)) {
699
// not pointing at the ground
700
range_ok = false;
701
} else {
702
corrected_distance = v.z;
703
}
704
}
705
706
if (range_ok && ahrs.home_is_set()) {
707
if (!rangefinder_state.have_initial_reading) {
708
rangefinder_state.have_initial_reading = true;
709
rangefinder_state.initial_range = distance;
710
}
711
rangefinder_state.height_estimate = corrected_distance;
712
713
rangefinder_terrain_correction(rangefinder_state.height_estimate);
714
715
// we consider ourselves to be fully in range when we have 10
716
// good samples (0.2s) that are different by 5% of the maximum
717
// range from the initial range we see. The 5% change is to
718
// catch Lidars that are giving a constant range, either due
719
// to misconfiguration or a faulty sensor
720
if (rangefinder_state.in_range_count < 10) {
721
if (!is_equal(distance, rangefinder_state.last_distance) &&
722
fabsf(rangefinder_state.initial_range - distance) > 0.05f * rangefinder.max_distance_cm_orient(rangefinder_orientation())*0.01f) {
723
rangefinder_state.in_range_count++;
724
}
725
if (fabsf(rangefinder_state.last_distance - distance) > rangefinder.max_distance_cm_orient(rangefinder_orientation())*0.01*0.2) {
726
// changes by more than 20% of full range will reset counter
727
rangefinder_state.in_range_count = 0;
728
}
729
} else {
730
rangefinder_state.in_range = true;
731
bool flightstage_good_for_rangefinder_landing = false;
732
if (flight_stage == AP_FixedWing::FlightStage::LAND) {
733
flightstage_good_for_rangefinder_landing = true;
734
}
735
#if HAL_QUADPLANE_ENABLED
736
if (control_mode == &mode_qland ||
737
control_mode == &mode_qrtl ||
738
(control_mode == &mode_auto && quadplane.is_vtol_land(plane.mission.get_current_nav_cmd().id))) {
739
flightstage_good_for_rangefinder_landing = true;
740
}
741
#endif
742
if (!rangefinder_state.in_use &&
743
flightstage_good_for_rangefinder_landing &&
744
g.rangefinder_landing) {
745
rangefinder_state.in_use = true;
746
gcs().send_text(MAV_SEVERITY_INFO, "Rangefinder engaged at %.2fm", (double)rangefinder_state.height_estimate);
747
}
748
}
749
rangefinder_state.last_distance = distance;
750
} else {
751
rangefinder_state.in_range_count = 0;
752
rangefinder_state.in_range = false;
753
}
754
755
if (rangefinder_state.in_range) {
756
// If not using terrain data, we expect zero correction when our height above target is equal to our rangefinder measurement
757
float correction = height_above_target() - rangefinder_state.height_estimate;
758
759
#if AP_TERRAIN_AVAILABLE
760
// if we are terrain following then correction is based on terrain data
761
float terrain_altitude;
762
if ((target_altitude.terrain_following || terrain_enabled_in_current_mode()) &&
763
terrain.height_above_terrain(terrain_altitude, true)) {
764
correction = terrain_altitude - rangefinder_state.height_estimate;
765
}
766
#endif
767
768
// remember the last correction. Use a low pass filter unless
769
// the old data is more than 5 seconds old
770
uint32_t now = millis();
771
if (now - rangefinder_state.last_correction_time_ms > 5000) {
772
rangefinder_state.correction = correction;
773
rangefinder_state.initial_correction = correction;
774
if (g.rangefinder_landing) {
775
landing.set_initial_slope();
776
}
777
rangefinder_state.last_correction_time_ms = now;
778
} else {
779
rangefinder_state.correction = 0.8f*rangefinder_state.correction + 0.2f*correction;
780
rangefinder_state.last_correction_time_ms = now;
781
if (fabsf(rangefinder_state.correction - rangefinder_state.initial_correction) > 30) {
782
// the correction has changed by more than 30m, reset use of Lidar. We may have a bad lidar
783
if (rangefinder_state.in_use) {
784
gcs().send_text(MAV_SEVERITY_INFO, "Rangefinder disengaged at %.2fm", (double)rangefinder_state.height_estimate);
785
}
786
memset(&rangefinder_state, 0, sizeof(rangefinder_state));
787
}
788
}
789
790
}
791
}
792
#endif // AP_RANGEFINDER_ENABLED
793
794
/*
795
determine if Non Auto Terrain Disable is active and allowed in present control mode
796
*/
797
bool Plane::terrain_disabled()
798
{
799
return control_mode->allows_terrain_disable() && non_auto_terrain_disable;
800
}
801
802
803
/*
804
Check if terrain following is enabled for the current mode
805
*/
806
#if AP_TERRAIN_AVAILABLE
807
const Plane::TerrainLookupTable Plane::Terrain_lookup[] = {
808
{Mode::Number::FLY_BY_WIRE_B, terrain_bitmask::FLY_BY_WIRE_B},
809
{Mode::Number::CRUISE, terrain_bitmask::CRUISE},
810
{Mode::Number::AUTO, terrain_bitmask::AUTO},
811
{Mode::Number::RTL, terrain_bitmask::RTL},
812
{Mode::Number::AVOID_ADSB, terrain_bitmask::AVOID_ADSB},
813
{Mode::Number::GUIDED, terrain_bitmask::GUIDED},
814
{Mode::Number::LOITER, terrain_bitmask::LOITER},
815
{Mode::Number::CIRCLE, terrain_bitmask::CIRCLE},
816
#if HAL_QUADPLANE_ENABLED
817
{Mode::Number::QRTL, terrain_bitmask::QRTL},
818
{Mode::Number::QLAND, terrain_bitmask::QLAND},
819
{Mode::Number::QLOITER, terrain_bitmask::QLOITER},
820
#endif
821
};
822
823
bool Plane::terrain_enabled_in_current_mode() const
824
{
825
return terrain_enabled_in_mode(control_mode->mode_number());
826
}
827
828
bool Plane::terrain_enabled_in_mode(Mode::Number num) const
829
{
830
// Global enable
831
if ((g.terrain_follow.get() & int32_t(terrain_bitmask::ALL)) != 0) {
832
return true;
833
}
834
835
// Specific enable
836
for (const struct TerrainLookupTable entry : Terrain_lookup) {
837
if (entry.mode_num == num) {
838
if ((g.terrain_follow.get() & int32_t(entry.bitmask)) != 0) {
839
return true;
840
}
841
break;
842
}
843
}
844
845
return false;
846
}
847
#endif
848
849
#if AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED
850
/*
851
handle a MAV_CMD_SET_HAGL request. The accuracy is ignored
852
*/
853
void Plane::handle_external_hagl(const mavlink_command_int_t &packet)
854
{
855
auto &hagl = plane.external_hagl;
856
hagl.hagl = packet.param1;
857
hagl.last_update_ms = AP_HAL::millis();
858
hagl.timeout_ms = uint32_t(packet.param3 * 1000);
859
}
860
861
/*
862
get HAGL from external source if current
863
*/
864
bool Plane::get_external_HAGL(float &height_agl)
865
{
866
auto &hagl = plane.external_hagl;
867
if (hagl.last_update_ms != 0) {
868
const uint32_t now_ms = AP_HAL::millis();
869
if (now_ms - hagl.last_update_ms <= hagl.timeout_ms) {
870
height_agl = hagl.hagl;
871
return true;
872
}
873
hagl.last_update_ms = 0;
874
}
875
return false;
876
}
877
#endif // AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED
878
879
/*
880
get height for landing. Set using_rangefinder to true if a rangefinder
881
or external HAGL source is active
882
*/
883
float Plane::get_landing_height(bool &rangefinder_active)
884
{
885
float height;
886
887
#if AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED
888
// if external HAGL is active use that
889
if (get_external_HAGL(height)) {
890
// ensure no terrain correction is applied - that is the job
891
// of the external system if it is wanted
892
auto_state.terrain_correction = 0;
893
894
// an external HAGL is considered to be a type of rangefinder
895
rangefinder_active = true;
896
return height;
897
}
898
#endif
899
900
// get basic height above target
901
height = height_above_target();
902
rangefinder_active = false;
903
904
#if AP_RANGEFINDER_ENABLED
905
// possibly correct with rangefinder
906
height -= rangefinder_correction();
907
rangefinder_active = g.rangefinder_landing && rangefinder_state.in_range;
908
#endif
909
910
return height;
911
}
912
913