AP_SmartRTL: allow compilation with HAL_LOGGING_ENABLED false

This commit is contained in:
Peter Barker 2023-07-14 10:58:08 +10:00 committed by Andrew Tridgell
parent 2d3fed9784
commit 5bb3e0aa18
2 changed files with 7 additions and 0 deletions

View File

@ -869,6 +869,7 @@ void AP_SmartRTL::deactivate(SRTL_Actions action, const char *reason)
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "SmartRTL deactivated: %s", reason);
}
#if HAL_LOGGING_ENABLED
// logging
void AP_SmartRTL::log_action(SRTL_Actions action, const Vector3f &point) const
{
@ -876,6 +877,7 @@ void AP_SmartRTL::log_action(SRTL_Actions action, const Vector3f &point) const
AP::logger().Write_SRTL(_active, _path_points_count, _path_points_max, action, point);
}
}
#endif
// returns true if the two loops overlap (used within add_loop to determine which loops to keep or throw away)
bool AP_SmartRTL::loops_overlap(const prune_loop_t &loop1, const prune_loop_t &loop2) const

View File

@ -3,6 +3,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/Bitmask.h>
#include <AP_Math/AP_Math.h>
#include <AP_Logger/AP_Logger_config.h>
// definitions and macros
#define SMARTRTL_ACCURACY_DEFAULT 2.0f // default _ACCURACY parameter value. Points will be no closer than this distance (in meters) together.
@ -172,8 +173,12 @@ private:
// de-activate SmartRTL, send warning to GCS and logger
void deactivate(SRTL_Actions action, const char *reason);
#if HAL_LOGGING_ENABLED
// logging
void log_action(SRTL_Actions action, const Vector3f &point = Vector3f()) const;
#else
void log_action(SRTL_Actions action, const Vector3f &point = Vector3f()) const {}
#endif
// parameters
AP_Float _accuracy;