mirror of https://github.com/ArduPilot/ardupilot
AP_SmartRTL: Add missing const in member functions
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
bffda55639
commit
0da2d9f8eb
|
@ -834,7 +834,7 @@ void AP_SmartRTL::deactivate(SRTL_Actions action, const char *reason)
|
||||||
}
|
}
|
||||||
|
|
||||||
// logging
|
// 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) {
|
if (!_example_mode) {
|
||||||
AP::logger().Write_SRTL(_active, _path_points_count, _path_points_max, action, point);
|
AP::logger().Write_SRTL(_active, _path_points_count, _path_points_max, action, point);
|
||||||
|
|
|
@ -159,7 +159,7 @@ private:
|
||||||
void deactivate(SRTL_Actions action, const char *reason);
|
void deactivate(SRTL_Actions action, const char *reason);
|
||||||
|
|
||||||
// logging
|
// logging
|
||||||
void log_action(SRTL_Actions action, const Vector3f &point = Vector3f());
|
void log_action(SRTL_Actions action, const Vector3f &point = Vector3f()) const;
|
||||||
|
|
||||||
// parameters
|
// parameters
|
||||||
AP_Float _accuracy;
|
AP_Float _accuracy;
|
||||||
|
|
Loading…
Reference in New Issue