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