Skip to content

Commit daaa522

Browse files
SteveMacenskidoisygGuillaume Doisy
committed
MPPI: Support Exact Path Following For Feasible Plans (#3659)
* alternative to path align critic for inversion control * fix default behavior (enforce_path_inversion: false) (#3643) Co-authored-by: Guillaume Doisy <guillaume@dexory.com> * adding dyaw option for path alignment to incentivize following the path's intent where necessary * add docs for use path orientations * fix typo --------- Co-authored-by: Guillaume Doisy <doisyg@users.noreply.github.com> Co-authored-by: Guillaume Doisy <guillaume@dexory.com>
1 parent 5efbe9f commit daaa522

File tree

8 files changed

+267
-23
lines changed

8 files changed

+267
-23
lines changed

nav2_mppi_controller/README.md

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -64,6 +64,9 @@ This process is then repeated a number of times and returns a converged solution
6464
| max_robot_pose_search_dist | double | Default: Costmap half-size. Max integrated distance ahead of robot pose to search for nearest path point in case of path looping. |
6565
| prune_distance | double | Default: 1.5. Distance ahead of nearest point on path to robot to prune path to. |
6666
| transform_tolerance | double | Default: 0.1. Time tolerance for data transformations with TF. |
67+
| enforce_path_inversion | double | Default: False. If true, it will prune paths containing cusping points for segments changing directions (e.g. path inversions) such that the controller will be forced to change directions at or very near the planner's requested inversion point. This is targeting Smac Planner users with feasible paths who need their robots to switch directions where specifically requested. |
68+
| inversion_xy_tolerance | double | Default: 0.2. Cartesian proximity (m) to path inversion point to be considered "achieved" to pass on the rest of the path after path inversion. |
69+
| inversion_yaw_tolerance | double | Default: 0.4. Angular proximity (radians) to path inversion point to be considered "achieved" to pass on the rest of the path after path inversion. 0.4 rad = 23 deg. |
6770

6871
#### Ackermann Motion Model
6972
| Parameter | Type | Definition |
@@ -111,6 +114,7 @@ This process is then repeated a number of times and returns a converged solution
111114
| offset_from_furthest | double | Default 20. Checks that the candidate trajectories are sufficiently far along their way tracking the path to apply the alignment critic. This ensures that path alignment is only considered when actually tracking the path, preventing awkward initialization motions preventing the robot from leaving the path to achieve the appropriate heading. |
112115
| trajectory_point_step | double | Default 4. Step of trajectory points to evaluate for path distance to reduce compute time. Between 1-10 is typically reasonable. |
113116
| 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. |
117+
| 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. |
114118

115119
#### Path Angle Critic
116120
| Parameter | Type | Definition |
@@ -211,6 +215,7 @@ controller_server:
211215
trajectory_point_step: 3
212216
threshold_to_consider: 0.5
213217
offset_from_furthest: 20
218+
use_path_orientations: false
214219
PathFollowCritic:
215220
enabled: true
216221
cost_power: 1

nav2_mppi_controller/include/nav2_mppi_controller/critics/path_align_critic.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -49,6 +49,7 @@ class PathAlignCritic : public CriticFunction
4949
int trajectory_point_step_{0};
5050
float threshold_to_consider_{0};
5151
float max_path_occupancy_ratio_{0};
52+
bool use_path_orientations_{false};
5253
unsigned int power_{0};
5354
float weight_{0};
5455
};

nav2_mppi_controller/include/nav2_mppi_controller/tools/path_handler.hpp

Lines changed: 17 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,6 @@
11
// Copyright (c) 2022 Samsung Research America, @artofnothingness Alexey Budyakov
2+
// Copyright (c) 2023 Dexory
3+
// Copyright (c) 2023 Open Navigation LLC
24
//
35
// Licensed under the Apache License, Version 2.0 (the "License");
46
// you may not use this file except in compliance with the License.
@@ -124,22 +126,35 @@ class PathHandler
124126
const geometry_msgs::msg::PoseStamped & global_pose);
125127

126128
/**
127-
* @brief Prune global path to only interesting portions
129+
* @brief Prune a path to only interesting portions
130+
* @param plan Plan to prune
128131
* @param end Final path iterator
129132
*/
130-
void pruneGlobalPlan(const PathIterator end);
133+
void prunePlan(nav_msgs::msg::Path & plan, const PathIterator end);
134+
135+
/**
136+
* @brief Check if the robot pose is within the set inversion tolerances
137+
* @param robot_pose Robot's current pose to check
138+
* @return bool If the robot pose is within the set inversion tolerances
139+
*/
140+
bool isWithinInversionTolerances(const geometry_msgs::msg::PoseStamped & robot_pose);
131141

132142
std::string name_;
133143
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_;
134144
std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
135145
ParametersHandler * parameters_handler_;
136146

137147
nav_msgs::msg::Path global_plan_;
148+
nav_msgs::msg::Path global_plan_up_to_inversion_;
138149
rclcpp::Logger logger_{rclcpp::get_logger("MPPIController")};
139150

140151
double max_robot_pose_search_dist_{0};
141152
double prune_distance_{0};
142153
double transform_tolerance_{0};
154+
double inversion_xy_tolerance_{0.2};
155+
double inversion_yaw_tolerance{0.4};
156+
bool enforce_path_inversion_{false};
157+
unsigned int inversion_locale_{0u};
143158
};
144159
} // namespace mppi
145160

nav2_mppi_controller/include/nav2_mppi_controller/tools/utils.hpp

Lines changed: 54 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,5 @@
11
// Copyright (c) 2022 Samsung Research America, @artofnothingness Alexey Budyakov
2+
// Copyright (c) 2023 Open Navigation LLC
23
//
34
// Licensed under the Apache License, Version 2.0 (the "License");
45
// you may not use this file except in compliance with the License.
@@ -634,6 +635,59 @@ inline void savitskyGolayFilter(
634635
control_sequence.wz(offset)};
635636
}
636637

638+
/**
639+
* @brief Find the iterator of the first pose at which there is an inversion on the path,
640+
* @param path to check for inversion
641+
* @return the first point after the inversion found in the path
642+
*/
643+
inline unsigned int findFirstPathInversion(nav_msgs::msg::Path & path)
644+
{
645+
// At least 3 poses for a possible inversion
646+
if (path.poses.size() < 3) {
647+
return path.poses.size();
648+
}
649+
650+
// Iterating through the path to determine the position of the path inversion
651+
for (unsigned int idx = 1; idx < path.poses.size() - 1; ++idx) {
652+
// We have two vectors for the dot product OA and AB. Determining the vectors.
653+
double oa_x = path.poses[idx].pose.position.x -
654+
path.poses[idx - 1].pose.position.x;
655+
double oa_y = path.poses[idx].pose.position.y -
656+
path.poses[idx - 1].pose.position.y;
657+
double ab_x = path.poses[idx + 1].pose.position.x -
658+
path.poses[idx].pose.position.x;
659+
double ab_y = path.poses[idx + 1].pose.position.y -
660+
path.poses[idx].pose.position.y;
661+
662+
// Checking for the existance of cusp, in the path, using the dot product.
663+
double dot_product = (oa_x * ab_x) + (oa_y * ab_y);
664+
if (dot_product < 0.0) {
665+
return idx + 1;
666+
}
667+
}
668+
669+
return path.poses.size();
670+
}
671+
672+
/**
673+
* @brief Find and remove poses after the first inversion in the path
674+
* @param path to check for inversion
675+
* @return The location of the inversion, return 0 if none exist
676+
*/
677+
inline unsigned int removePosesAfterFirstInversion(nav_msgs::msg::Path & path)
678+
{
679+
nav_msgs::msg::Path cropped_path = path;
680+
const unsigned int first_after_inversion = findFirstPathInversion(cropped_path);
681+
if (first_after_inversion == path.poses.size()) {
682+
return 0u;
683+
}
684+
685+
cropped_path.poses.erase(
686+
cropped_path.poses.begin() + first_after_inversion, cropped_path.poses.end());
687+
path = cropped_path;
688+
return first_after_inversion;
689+
}
690+
637691
} // namespace mppi::utils
638692

639693
#endif // NAV2_MPPI_CONTROLLER__TOOLS__UTILS_HPP_

nav2_mppi_controller/src/critics/path_align_critic.cpp

Lines changed: 18 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,7 @@ void PathAlignCritic::initialize()
3535
getParam(
3636
threshold_to_consider_,
3737
"threshold_to_consider", 0.5);
38+
getParam(use_path_orientations_, "use_path_orientations", false);
3839

3940
RCLCPP_INFO(
4041
logger_,
@@ -71,9 +72,11 @@ void PathAlignCritic::score(CriticData & data)
7172

7273
const auto & T_x = data.trajectories.x;
7374
const auto & T_y = data.trajectories.y;
75+
const auto & T_yaw = data.trajectories.yaws;
7476

7577
const auto P_x = xt::view(data.path.x, xt::range(_, -1)); // path points
7678
const auto P_y = xt::view(data.path.y, xt::range(_, -1)); // path points
79+
const auto P_yaw = xt::view(data.path.yaws, xt::range(_, -1)); // path points
7780

7881
const size_t batch_size = T_x.shape(0);
7982
const size_t time_steps = T_x.shape(1);
@@ -85,18 +88,27 @@ void PathAlignCritic::score(CriticData & data)
8588
return;
8689
}
8790

91+
float dist_sq = 0, dx = 0, dy = 0, dyaw = 0, summed_dist = 0;
92+
double min_dist_sq = std::numeric_limits<float>::max();
93+
size_t min_s = 0;
94+
8895
for (size_t t = 0; t < batch_size; ++t) {
89-
float summed_dist = 0;
96+
summed_dist = 0;
9097
for (size_t p = trajectory_point_step_; p < time_steps; p += trajectory_point_step_) {
91-
double min_dist_sq = std::numeric_limits<float>::max();
92-
size_t min_s = 0;
98+
min_dist_sq = std::numeric_limits<float>::max();
99+
min_s = 0;
93100

94101
// Find closest path segment to the trajectory point
95102
for (size_t s = 0; s < path_segments_count - 1; s++) {
96103
xt::xtensor_fixed<float, xt::xshape<2>> P;
97-
float dx = P_x(s) - T_x(t, p);
98-
float dy = P_y(s) - T_y(t, p);
99-
float dist_sq = dx * dx + dy * dy;
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+
}
100112
if (dist_sq < min_dist_sq) {
101113
min_dist_sq = dist_sq;
102114
min_s = s;

nav2_mppi_controller/src/path_handler.cpp

Lines changed: 44 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,6 @@
11
// Copyright (c) 2022 Samsung Research America, @artofnothingness Alexey Budyakov
2+
// Copyright (c) 2023 Dexory
3+
// Copyright (c) 2023 Open Navigation LLC
24
//
35
// Licensed under the Apache License, Version 2.0 (the "License");
46
// you may not use this file except in compliance with the License.
@@ -35,6 +37,12 @@ void PathHandler::initialize(
3537
getParam(max_robot_pose_search_dist_, "max_robot_pose_search_dist", getMaxCostmapDist());
3638
getParam(prune_distance_, "prune_distance", 1.5);
3739
getParam(transform_tolerance_, "transform_tolerance", 0.1);
40+
getParam(enforce_path_inversion_, "enforce_path_inversion", false);
41+
if (enforce_path_inversion_) {
42+
getParam(inversion_xy_tolerance_, "inversion_xy_tolerance", 0.2);
43+
getParam(inversion_yaw_tolerance, "inversion_yaw_tolerance", 0.4);
44+
inversion_locale_ = 0u;
45+
}
3846
}
3947

4048
std::pair<nav_msgs::msg::Path, PathIterator>
@@ -43,12 +51,13 @@ PathHandler::getGlobalPlanConsideringBoundsInCostmapFrame(
4351
{
4452
using nav2_util::geometry_utils::euclidean_distance;
4553

46-
auto begin = global_plan_.poses.begin();
54+
auto begin = global_plan_up_to_inversion_.poses.begin();
4755

4856
// Limit the search for the closest pose up to max_robot_pose_search_dist on the path
4957
auto closest_pose_upper_bound =
5058
nav2_util::geometry_utils::first_after_integrated_distance(
51-
global_plan_.poses.begin(), global_plan_.poses.end(), max_robot_pose_search_dist_);
59+
global_plan_up_to_inversion_.poses.begin(), global_plan_up_to_inversion_.poses.end(),
60+
max_robot_pose_search_dist_);
5261

5362
// Find closest point to the robot
5463
auto closest_point = nav2_util::geometry_utils::min_by(
@@ -63,7 +72,7 @@ PathHandler::getGlobalPlanConsideringBoundsInCostmapFrame(
6372

6473
auto pruned_plan_end =
6574
nav2_util::geometry_utils::first_after_integrated_distance(
66-
closest_point, global_plan_.poses.end(), prune_distance_);
75+
closest_point, global_plan_up_to_inversion_.poses.end(), prune_distance_);
6776

6877
unsigned int mx, my;
6978
// Find the furthest relevent pose on the path to consider within costmap
@@ -95,12 +104,12 @@ PathHandler::getGlobalPlanConsideringBoundsInCostmapFrame(
95104
geometry_msgs::msg::PoseStamped PathHandler::transformToGlobalPlanFrame(
96105
const geometry_msgs::msg::PoseStamped & pose)
97106
{
98-
if (global_plan_.poses.empty()) {
107+
if (global_plan_up_to_inversion_.poses.empty()) {
99108
throw nav2_core::InvalidPath("Received plan with zero length");
100109
}
101110

102111
geometry_msgs::msg::PoseStamped robot_pose;
103-
if (!transformPose(global_plan_.header.frame_id, pose, robot_pose)) {
112+
if (!transformPose(global_plan_up_to_inversion_.header.frame_id, pose, robot_pose)) {
104113
throw nav2_core::ControllerTFError(
105114
"Unable to transform robot pose into global plan's frame");
106115
}
@@ -116,7 +125,15 @@ nav_msgs::msg::Path PathHandler::transformPath(
116125
transformToGlobalPlanFrame(robot_pose);
117126
auto [transformed_plan, lower_bound] = getGlobalPlanConsideringBoundsInCostmapFrame(global_pose);
118127

119-
pruneGlobalPlan(lower_bound);
128+
prunePlan(global_plan_up_to_inversion_, lower_bound);
129+
130+
if (enforce_path_inversion_ && inversion_locale_ != 0u) {
131+
if (isWithinInversionTolerances(global_pose)) {
132+
prunePlan(global_plan_, global_plan_.poses.begin() + inversion_locale_);
133+
global_plan_up_to_inversion_ = global_plan_;
134+
inversion_locale_ = utils::removePosesAfterFirstInversion(global_plan_up_to_inversion_);
135+
}
136+
}
120137

121138
if (transformed_plan.poses.empty()) {
122139
throw nav2_core::InvalidPath("Resulting plan has 0 poses in it.");
@@ -156,13 +173,32 @@ double PathHandler::getMaxCostmapDist()
156173
void PathHandler::setPath(const nav_msgs::msg::Path & plan)
157174
{
158175
global_plan_ = plan;
176+
global_plan_up_to_inversion_ = global_plan_;
177+
if (enforce_path_inversion_) {
178+
inversion_locale_ = utils::removePosesAfterFirstInversion(global_plan_up_to_inversion_);
179+
}
159180
}
160181

161182
nav_msgs::msg::Path & PathHandler::getPath() {return global_plan_;}
162183

163-
void PathHandler::pruneGlobalPlan(const PathIterator end)
184+
void PathHandler::prunePlan(nav_msgs::msg::Path & plan, const PathIterator end)
164185
{
165-
global_plan_.poses.erase(global_plan_.poses.begin(), end);
186+
plan.poses.erase(plan.poses.begin(), end);
187+
}
188+
189+
bool PathHandler::isWithinInversionTolerances(const geometry_msgs::msg::PoseStamped & robot_pose)
190+
{
191+
// Keep full path if we are within tolerance of the inversion pose
192+
const auto last_pose = global_plan_up_to_inversion_.poses.back();
193+
double distance = std::hypot(
194+
robot_pose.pose.position.x - last_pose.pose.position.x,
195+
robot_pose.pose.position.y - last_pose.pose.position.y);
196+
197+
double angle_distance = angles::shortest_angular_distance(
198+
tf2::getYaw(robot_pose.pose.orientation),
199+
tf2::getYaw(last_pose.pose.orientation));
200+
201+
return distance <= inversion_xy_tolerance_ && fabs(angle_distance) <= inversion_yaw_tolerance;
166202
}
167203

168204
} // namespace mppi

0 commit comments

Comments
 (0)