Skip to content

Commit

Permalink
AC_Avoidance: Dijsktras comment and const fix
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 committed Dec 27, 2023
1 parent 58b6429 commit 6c24f80
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions libraries/AC_Avoidance/AP_OADijkstra.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -179,7 +179,7 @@ AP_OADijkstra::AP_OADijkstra_State AP_OADijkstra::update(const Location &current

// path has been created, return latest point
Vector2f dest_pos;
uint8_t path_length = get_shortest_path_numpoints() > 0 ? (get_shortest_path_numpoints() - 1) : 0;
const uint8_t path_length = get_shortest_path_numpoints() > 0 ? (get_shortest_path_numpoints() - 1) : 0;
if ((_path_idx_returned < path_length) && get_shortest_path_point(_path_idx_returned, dest_pos)) {

// for the first point return origin as current_loc
Expand All @@ -199,7 +199,7 @@ AP_OADijkstra::AP_OADijkstra_State AP_OADijkstra::update(const Location &current
destination_new.lat = temp_loc.lat;
destination_new.lng = temp_loc.lng;

// if present also provide next destination if present to allow smooth cornering
// provide next destination to allow smooth cornering
next_destination_new.zero();
Vector2f next_dest_pos;
if ((_path_idx_returned + 1 < path_length) && get_shortest_path_point(_path_idx_returned + 1, next_dest_pos)) {
Expand Down

0 comments on commit 6c24f80

Please sign in to comment.