ardupilot/ArduSub/terrain.cpp

39 lines
830 B
C++
Raw Permalink Normal View History

2016-05-03 22:57:47 -03:00
#include "Sub.h"
// update terrain data
void Sub::terrain_update()
{
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
terrain.update();
// tell the rangefinder our height, so it can go into power saving
// mode if available
#if RANGEFINDER_ENABLED == ENABLED
2016-05-03 22:57:47 -03:00
float height;
if (terrain.height_above_terrain(height, true)) {
rangefinder.set_estimated_terrain_height(height);
2016-05-03 22:57:47 -03:00
}
#endif
#endif
}
// log terrain data - should be called at 1hz
void Sub::terrain_logging()
{
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
if (should_log(MASK_LOG_GPS)) {
terrain.log_terrain_data(DataFlash);
}
#endif
}
// should we use terrain data for things including the home altitude
bool Sub::terrain_use()
{
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
return (g.terrain_follow > 0);
#else
return false;
#endif
}