APM:Copter
ArduCopter
terrain.cpp
Go to the documentation of this file.
1
#include "
Copter.h
"
2
3
// update terrain data
4
void
Copter::terrain_update
()
5
{
6
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
7
terrain
.update();
8
9
// tell the rangefinder our height, so it can go into power saving
10
// mode if available
11
#if RANGEFINDER_ENABLED == ENABLED
12
float
height;
13
if
(
terrain
.height_above_terrain(height,
true
)) {
14
rangefinder
.
set_estimated_terrain_height
(height);
15
}
16
#endif
17
#endif
18
}
19
20
// log terrain data - should be called at 1hz
21
void
Copter::terrain_logging
()
22
{
23
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
24
if
(
should_log
(
MASK_LOG_GPS
)) {
25
terrain
.log_terrain_data(
DataFlash
);
26
}
27
#endif
28
}
29
30
// should we use terrain data for things including the home altitude
31
bool
Copter::terrain_use
()
32
{
33
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
34
return
(
g
.terrain_follow > 0);
35
#else
36
return
false
;
37
#endif
38
}
Copter::terrain_use
bool terrain_use()
Definition:
terrain.cpp:31
MASK_LOG_GPS
#define MASK_LOG_GPS
Definition:
defines.h:316
Copter::rangefinder
RangeFinder rangefinder
Definition:
Copter.h:238
RangeFinder::set_estimated_terrain_height
void set_estimated_terrain_height(float height)
Copter::terrain_logging
void terrain_logging()
Definition:
terrain.cpp:21
Copter::should_log
bool should_log(uint32_t mask)
Definition:
system.cpp:435
Copter::terrain_update
void terrain_update()
Definition:
terrain.cpp:4
Copter::terrain
uint8_t terrain
Definition:
Copter.h:400
Copter::DataFlash
DataFlash_Class DataFlash
Definition:
Copter.h:227
Copter::g
Parameters g
Definition:
Copter.h:208
Copter.h
Generated on Sun Jun 17 2018 14:37:57 for APM:Copter by
1.8.13