Skip to content

Commit 7009ffb

Browse files
[MPPI] Reworked Path Align Critic; 70% faster + Tracks Paths Better! Edit: strike that, now 80% (#3872)
* adding regenerate noise param + adding docs * fix tests * remove unnecessary normalization * Update optimizer.cpp * adding refactored path alignment critic * fix visualization bug * speed up another 30% * remove a little jitter * a few more small optimizaitons * fixing unit tests * retain legacy critic * adding tests for legacy
1 parent 461a7ba commit 7009ffb

File tree

11 files changed

+380
-47
lines changed

11 files changed

+380
-47
lines changed

nav2_mppi_controller/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -78,6 +78,7 @@ add_library(mppi_critics SHARED
7878
src/critics/goal_critic.cpp
7979
src/critics/goal_angle_critic.cpp
8080
src/critics/path_align_critic.cpp
81+
src/critics/path_align_legacy_critic.cpp
8182
src/critics/path_follow_critic.cpp
8283
src/critics/path_angle_critic.cpp
8384
src/critics/prefer_forward_critic.cpp

nav2_mppi_controller/LICENSE.md

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,7 @@ MIT License
22

33
Copyright (c) 2021-2022 Fast Sense Studio
44
Copyright (c) 2022-2023 Samsung Research America
5+
Copyright (c) 2023 Open Navigation LLC
56

67
Permission is hereby granted, free of charge, to any person obtaining a copy
78
of this software and associated documentation files (the "Software"), to deal

nav2_mppi_controller/README.md

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -119,6 +119,8 @@ This process is then repeated a number of times and returns a converged solution
119119
| max_path_occupancy_ratio | double | Default 0.07 (7%). Maximum proportion of the path that can be occupied before this critic is not considered to allow the obstacle and path follow critics to avoid obstacles while following the path's intent in presence of dynamic objects in the scene. |
120120
| use_path_orientations | bool | Default false. Whether to consider path's orientations in path alignment, which can be useful when paired with feasible smac planners to incentivize directional changes only where/when the smac planner requests them. If you want the robot to deviate and invert directions where the controller sees fit, keep as false. If your plans do not contain orientation information (e.g. navfn), keep as false. |
121121

122+
Note: There is a "Legacy" version of this critic also available with the same parameters of an old formulation pre-October 2023.
123+
122124
#### Path Angle Critic
123125
| Parameter | Type | Definition |
124126
| --------------- | ------ | ----------------------------------------------------------------------------------------------------------- |

nav2_mppi_controller/critics.xml

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,10 @@
1717
<description>mppi critic for aligning to path</description>
1818
</class>
1919

20+
<class type="mppi::critics::PathAlignLegacyCritic" base_class_type="mppi::critics::CriticFunction">
21+
<description>mppi critic for aligning to path (legacy)</description>
22+
</class>
23+
2024
<class type="mppi::critics::PathAngleCritic" base_class_type="mppi::critics::CriticFunction">
2125
<description>mppi critic for tracking the path in the correct heading</description>
2226
</class>

nav2_mppi_controller/include/nav2_mppi_controller/critics/path_align_critic.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright (c) 2022 Samsung Research America, @artofnothingness Alexey Budyakov
1+
// Copyright (c) 2023 Open Navigation LLC
22
//
33
// Licensed under the Apache License, Version 2.0 (the "License");
44
// you may not use this file except in compliance with the License.
Lines changed: 60 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,60 @@
1+
// Copyright (c) 2022 Samsung Research America, @artofnothingness Alexey Budyakov
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef NAV2_MPPI_CONTROLLER__CRITICS__PATH_ALIGN_LEGACY_CRITIC_HPP_
16+
#define NAV2_MPPI_CONTROLLER__CRITICS__PATH_ALIGN_LEGACY_CRITIC_HPP_
17+
18+
#include "nav2_mppi_controller/critic_function.hpp"
19+
#include "nav2_mppi_controller/models/state.hpp"
20+
#include "nav2_mppi_controller/tools/utils.hpp"
21+
22+
namespace mppi::critics
23+
{
24+
25+
/**
26+
* @class mppi::critics::PathAlignLegacyCritic
27+
* @brief Critic objective function for aligning to the path. Note:
28+
* High settings of this will follow the path more precisely, but also makes it
29+
* difficult (or impossible) to deviate in the presence of dynamic obstacles.
30+
* This is an important critic to tune and consider in tandem with Obstacle.
31+
* This is the initial 'Legacy' implementation before replacement Oct 2023.
32+
*/
33+
class PathAlignLegacyCritic : public CriticFunction
34+
{
35+
public:
36+
/**
37+
* @brief Initialize critic
38+
*/
39+
void initialize() override;
40+
41+
/**
42+
* @brief Evaluate cost related to trajectories path alignment
43+
*
44+
* @param costs [out] add reference cost values to this tensor
45+
*/
46+
void score(CriticData & data) override;
47+
48+
protected:
49+
size_t offset_from_furthest_{0};
50+
int trajectory_point_step_{0};
51+
float threshold_to_consider_{0};
52+
float max_path_occupancy_ratio_{0};
53+
bool use_path_orientations_{false};
54+
unsigned int power_{0};
55+
float weight_{0};
56+
};
57+
58+
} // namespace mppi::critics
59+
60+
#endif // NAV2_MPPI_CONTROLLER__CRITICS__PATH_ALIGN_LEGACY_CRITIC_HPP_

nav2_mppi_controller/include/nav2_mppi_controller/tools/utils.hpp

Lines changed: 23 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -308,14 +308,16 @@ inline size_t findPathFurthestReachedPoint(const CriticData & data)
308308

309309
const auto dists = dx * dx + dy * dy;
310310

311-
size_t max_id_by_trajectories = 0;
311+
size_t max_id_by_trajectories = 0, min_id_by_path = 0;
312312
float min_distance_by_path = std::numeric_limits<float>::max();
313+
float cur_dist = 0.0f;
313314

314315
for (size_t i = 0; i < dists.shape(0); i++) {
315-
size_t min_id_by_path = 0;
316+
min_id_by_path = 0;
316317
for (size_t j = 0; j < dists.shape(1); j++) {
317-
if (dists(i, j) < min_distance_by_path) {
318-
min_distance_by_path = dists(i, j);
318+
cur_dist = dists(i, j);
319+
if (cur_dist < min_distance_by_path) {
320+
min_distance_by_path = cur_dist;
319321
min_id_by_path = j;
320322
}
321323
}
@@ -688,6 +690,23 @@ inline unsigned int removePosesAfterFirstInversion(nav_msgs::msg::Path & path)
688690
return first_after_inversion;
689691
}
690692

693+
/**
694+
* @brief Compare to trajectory points to find closest path point along integrated distances
695+
* @param vec Vect to check
696+
* @return dist Distance to look for
697+
*/
698+
inline size_t findClosestPathPt(const std::vector<float> & vec, float dist, size_t init = 0)
699+
{
700+
auto iter = std::lower_bound(vec.begin() + init, vec.end(), dist);
701+
if (iter == vec.begin()) {
702+
return 0;
703+
}
704+
if (dist - *(iter - 1) < *iter - dist) {
705+
return iter - 1 - vec.begin();
706+
}
707+
return iter - vec.begin();
708+
}
709+
691710
} // namespace mppi::utils
692711

693712
#endif // NAV2_MPPI_CONTROLLER__TOOLS__UTILS_HPP_

nav2_mppi_controller/src/critics/path_align_critic.cpp

Lines changed: 44 additions & 40 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright (c) 2022 Samsung Research America, @artofnothingness Alexey Budyakov
1+
// Copyright (c) 2023 Open Navigation LLC
22
//
33
// Licensed under the Apache License, Version 2.0 (the "License");
44
// you may not use this file except in compliance with the License.
@@ -54,7 +54,8 @@ void PathAlignCritic::score(CriticData & data)
5454

5555
// Don't apply when first getting bearing w.r.t. the path
5656
utils::setPathFurthestPointIfNotSet(data);
57-
if (*data.furthest_reached_path_point < offset_from_furthest_) {
57+
const size_t path_segments_count = *data.furthest_reached_path_point; // up to furthest only
58+
if (path_segments_count < offset_from_furthest_) {
5859
return;
5960
}
6061

@@ -70,59 +71,62 @@ void PathAlignCritic::score(CriticData & data)
7071
}
7172
}
7273

73-
const auto & T_x = data.trajectories.x;
74-
const auto & T_y = data.trajectories.y;
75-
const auto & T_yaw = data.trajectories.yaws;
76-
7774
const auto P_x = xt::view(data.path.x, xt::range(_, -1)); // path points
7875
const auto P_y = xt::view(data.path.y, xt::range(_, -1)); // path points
7976
const auto P_yaw = xt::view(data.path.yaws, xt::range(_, -1)); // path points
8077

81-
const size_t batch_size = T_x.shape(0);
82-
const size_t time_steps = T_x.shape(1);
83-
const size_t traj_pts_eval = floor(time_steps / trajectory_point_step_);
84-
const size_t path_segments_count = data.path.x.shape(0) - 1;
78+
const size_t batch_size = data.trajectories.x.shape(0);
79+
const size_t time_steps = data.trajectories.x.shape(1);
8580
auto && cost = xt::xtensor<float, 1>::from_shape({data.costs.shape(0)});
8681

87-
if (path_segments_count < 1) {
88-
return;
82+
// Find integrated distance in the path
83+
std::vector<float> path_integrated_distances(path_segments_count, 0.0f);
84+
float dx = 0.0f, dy = 0.0f;
85+
for (unsigned int i = 1; i != path_segments_count; i++) {
86+
dx = P_x(i) - P_x(i - 1);
87+
dy = P_y(i) - P_y(i - 1);
88+
float curr_dist = sqrtf(dx * dx + dy * dy);
89+
path_integrated_distances[i] = path_integrated_distances[i - 1] + curr_dist;
8990
}
9091

91-
float dist_sq = 0.0f, dx = 0.0f, dy = 0.0f, dyaw = 0.0f, summed_dist = 0.0f;
92-
float min_dist_sq = std::numeric_limits<float>::max();
93-
size_t min_s = 0;
94-
92+
float traj_integrated_distance = 0.0f;
93+
float summed_path_dist = 0.0f, dyaw = 0.0f;
94+
float num_samples = 0.0f;
95+
float Tx = 0.0f, Ty = 0.0f;
96+
size_t path_pt = 0;
9597
for (size_t t = 0; t < batch_size; ++t) {
96-
summed_dist = 0.0f;
98+
traj_integrated_distance = 0.0f;
99+
summed_path_dist = 0.0f;
100+
num_samples = 0.0f;
101+
const auto T_x = xt::view(data.trajectories.x, t, xt::all());
102+
const auto T_y = xt::view(data.trajectories.y, t, xt::all());
97103
for (size_t p = trajectory_point_step_; p < time_steps; p += trajectory_point_step_) {
98-
min_dist_sq = std::numeric_limits<float>::max();
99-
min_s = 0;
100-
101-
// Find closest path segment to the trajectory point
102-
for (size_t s = 0; s < path_segments_count - 1; s++) {
103-
xt::xtensor_fixed<float, xt::xshape<2>> P;
104-
dx = P_x(s) - T_x(t, p);
105-
dy = P_y(s) - T_y(t, p);
106-
if (use_path_orientations_) {
107-
dyaw = angles::shortest_angular_distance(P_yaw(s), T_yaw(t, p));
108-
dist_sq = dx * dx + dy * dy + dyaw * dyaw;
109-
} else {
110-
dist_sq = dx * dx + dy * dy;
111-
}
112-
if (dist_sq < min_dist_sq) {
113-
min_dist_sq = dist_sq;
114-
min_s = s;
115-
}
116-
}
104+
Tx = T_x(p);
105+
Ty = T_y(p);
106+
dx = Tx - T_x(p - trajectory_point_step_);
107+
dy = Ty - T_y(p - trajectory_point_step_);
108+
traj_integrated_distance += sqrtf(dx * dx + dy * dy);
109+
path_pt = utils::findClosestPathPt(
110+
path_integrated_distances, traj_integrated_distance, path_pt);
117111

118112
// The nearest path point to align to needs to be not in collision, else
119113
// let the obstacle critic take over in this region due to dynamic obstacles
120-
if (min_s != 0 && (*data.path_pts_valid)[min_s]) {
121-
summed_dist += sqrtf(min_dist_sq);
114+
if ((*data.path_pts_valid)[path_pt]) {
115+
dx = P_x(path_pt) - Tx;
116+
dy = P_y(path_pt) - Ty;
117+
num_samples += 1.0f;
118+
if (use_path_orientations_) {
119+
const auto T_yaw = xt::view(data.trajectories.yaws, t, xt::all());
120+
dyaw = angles::shortest_angular_distance(P_yaw(path_pt), T_yaw(p));
121+
summed_path_dist += sqrtf(dx * dx + dy * dy + dyaw * dyaw);
122+
} else {
123+
summed_path_dist += sqrtf(dx * dx + dy * dy);
124+
}
122125
}
123126
}
124-
125-
cost[t] = summed_dist / traj_pts_eval;
127+
if (num_samples > 0) {
128+
cost[t] = summed_path_dist / num_samples;
129+
}
126130
}
127131

128132
data.costs += xt::pow(std::move(cost) * weight_, power_);

0 commit comments

Comments
 (0)