mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
AC_Avoidance: constify get_shortest_path_point
This commit is contained in:
parent
1e626a70cb
commit
d01a330588
@ -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;
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user