diff --git a/libraries/AC_Avoidance/AP_OADijkstra.cpp b/libraries/AC_Avoidance/AP_OADijkstra.cpp index 749cb140ee..8a0913c63b 100644 --- a/libraries/AC_Avoidance/AP_OADijkstra.cpp +++ b/libraries/AC_Avoidance/AP_OADijkstra.cpp @@ -934,7 +934,7 @@ bool AP_OADijkstra::calc_shortest_path(const Location &origin, const Location &d } // return point from final path as an offset (in cm) from the ekf origin -bool AP_OADijkstra::get_shortest_path_point(uint8_t point_num, Vector2f& pos) +bool AP_OADijkstra::get_shortest_path_point(uint8_t point_num, Vector2f& pos) const { if ((_path_numpoints == 0) || (point_num >= _path_numpoints)) { return false; diff --git a/libraries/AC_Avoidance/AP_OADijkstra.h b/libraries/AC_Avoidance/AP_OADijkstra.h index 48e91f6cc1..b37b644c44 100644 --- a/libraries/AC_Avoidance/AP_OADijkstra.h +++ b/libraries/AC_Avoidance/AP_OADijkstra.h @@ -182,7 +182,7 @@ private: Vector2f _path_destination; // destination position used in shortest path calculations (offset in cm from EKF origin) // return point from final path as an offset (in cm) from the ekf origin - bool get_shortest_path_point(uint8_t point_num, Vector2f& pos); + bool get_shortest_path_point(uint8_t point_num, Vector2f& pos) const; // find the position of a node as an offset (in cm) from the ekf origin // returns true if successful and pos is updated