APM:Copter
ArduCopter
precision_landing.cpp
Go to the documentation of this file.
1
//
2
// functions to support precision landing
3
//
4
5
#include "
Copter.h
"
6
7
#if PRECISION_LANDING == ENABLED
8
9
void
Copter::init_precland
()
10
{
11
copter
.precland.init();
12
}
13
14
void
Copter::update_precland
()
15
{
16
int32_t height_above_ground_cm =
current_loc
.
alt
;
17
18
// use range finder altitude if it is valid, else try to get terrain alt
19
if
(
rangefinder_alt_ok
()) {
20
height_above_ground_cm =
rangefinder_state
.alt_cm;
21
}
else
if
(
terrain_use
()) {
22
if
(!
current_loc
.
get_alt_cm
(
Location_Class::ALT_FRAME_ABOVE_TERRAIN
, height_above_ground_cm)) {
23
height_above_ground_cm =
current_loc
.
alt
;
24
}
25
}
26
27
copter
.precland.update(height_above_ground_cm,
rangefinder_alt_ok
());
28
}
29
#endif
Copter::rangefinder_alt_ok
bool rangefinder_alt_ok()
Definition:
sensors.cpp:69
Copter::terrain_use
bool terrain_use()
Definition:
terrain.cpp:31
Copter::rangefinder_state
struct Copter::@0 rangefinder_state
Copter::init_precland
void init_precland()
Definition:
precision_landing.cpp:9
Location::alt
int32_t alt
Location_Class::get_alt_cm
bool get_alt_cm(ALT_FRAME desired_frame, int32_t &ret_alt_cm) const
Copter::current_loc
Location_Class current_loc
Definition:
Copter.h:475
Copter::update_precland
void update_precland()
Definition:
precision_landing.cpp:14
copter
AP_HAL_MAIN_CALLBACKS & copter
Definition:
ArduCopter.cpp:581
Copter.h
Location_Class::ALT_FRAME_ABOVE_TERRAIN
ALT_FRAME_ABOVE_TERRAIN
Generated on Sun Jun 17 2018 14:37:57 for APM:Copter by
1.8.13