mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Terrain: allow compilation with HAL_LOGGING_ENABLED false
This commit is contained in:
parent
3ae9e36bd3
commit
573a7b172e
@ -26,6 +26,7 @@
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||
#include <AP_Filesystem/AP_Filesystem.h>
|
||||
#include <AP_Rally/AP_Rally.h>
|
||||
|
||||
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
|
||||
|
@ -27,6 +27,7 @@
|
||||
#include <AP_Common/Location.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include <AP_Logger/AP_Logger_config.h>
|
||||
|
||||
#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
|
||||
|
Loading…
Reference in New Issue
Block a user