diff --git a/libraries/AP_Terrain/AP_Terrain.cpp b/libraries/AP_Terrain/AP_Terrain.cpp index 7e9e754036..d2aab8bf1d 100644 --- a/libraries/AP_Terrain/AP_Terrain.cpp +++ b/libraries/AP_Terrain/AP_Terrain.cpp @@ -26,6 +26,7 @@ #include #include #include +#include extern const AP_HAL::HAL& hal; @@ -439,6 +440,7 @@ bool AP_Terrain::pre_arm_checks(char *failure_msg, uint8_t failure_msg_len) cons return true; } +#if HAL_LOGGING_ENABLED void AP_Terrain::log_terrain_data() { if (!allocate()) { @@ -472,6 +474,7 @@ void AP_Terrain::log_terrain_data() }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); } +#endif /* allocate terrain cache. Making this dynamically allocated allows diff --git a/libraries/AP_Terrain/AP_Terrain.h b/libraries/AP_Terrain/AP_Terrain.h index ff55ce0dbb..8a6be4579d 100644 --- a/libraries/AP_Terrain/AP_Terrain.h +++ b/libraries/AP_Terrain/AP_Terrain.h @@ -27,6 +27,7 @@ #include #include #include +#include #define TERRAIN_DEBUG 0 @@ -172,10 +173,12 @@ public: */ float lookahead(float bearing, float distance, float climb_ratio); +#if HAL_LOGGING_ENABLED /* log terrain status to AP_Logger */ void log_terrain_data(); +#endif /* get some statistics for TERRAIN_REPORT