ardupilot/ArduCopter/terrain.cpp
Randy Mackay 3e7fb66a77 Copter: precision landing does not use terrain database
precision landing was always only using the range finder, there was no use of the provided alt unless the rangefinder was good
2019-12-17 20:02:01 +09:00

29 lines
627 B
C++

#include "Copter.h"
// update terrain data
void Copter::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
float height;
if (terrain.height_above_terrain(height, true)) {
rangefinder.set_estimated_terrain_height(height);
}
#endif
#endif
}
// log terrain data - should be called at 1hz
void Copter::terrain_logging()
{
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
if (should_log(MASK_LOG_GPS)) {
terrain.log_terrain_data();
}
#endif
}