diff --git a/libraries/AP_SmartRTL/AP_SmartRTL.cpp b/libraries/AP_SmartRTL/AP_SmartRTL.cpp index a577cc4989..26280e5fde 100644 --- a/libraries/AP_SmartRTL/AP_SmartRTL.cpp +++ b/libraries/AP_SmartRTL/AP_SmartRTL.cpp @@ -834,7 +834,7 @@ void AP_SmartRTL::deactivate(SRTL_Actions action, const char *reason) } // logging -void AP_SmartRTL::log_action(SRTL_Actions action, const Vector3f &point) +void AP_SmartRTL::log_action(SRTL_Actions action, const Vector3f &point) const { if (!_example_mode) { AP::logger().Write_SRTL(_active, _path_points_count, _path_points_max, action, point); diff --git a/libraries/AP_SmartRTL/AP_SmartRTL.h b/libraries/AP_SmartRTL/AP_SmartRTL.h index 08a4631c2c..a583729c0a 100644 --- a/libraries/AP_SmartRTL/AP_SmartRTL.h +++ b/libraries/AP_SmartRTL/AP_SmartRTL.h @@ -159,7 +159,7 @@ private: void deactivate(SRTL_Actions action, const char *reason); // logging - void log_action(SRTL_Actions action, const Vector3f &point = Vector3f()); + void log_action(SRTL_Actions action, const Vector3f &point = Vector3f()) const; // parameters AP_Float _accuracy;