Skip to content

Commit 586d292

Browse files
committed
updating mppi's path angle critic for optional bidirectionality (#3624)
* updating mppi's path angle critic for optional bidirectionality * Update README.md
1 parent 7671a4d commit 586d292

File tree

6 files changed

+58
-12
lines changed

6 files changed

+58
-12
lines changed

nav2_mppi_controller/README.md

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -116,7 +116,6 @@ This process is then repeated a number of times and returns a converged solution
116116
| 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. |
117117
| 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. |
118118

119-
120119
#### Path Angle Critic
121120
| Parameter | Type | Definition |
122121
| --------------- | ------ | ----------------------------------------------------------------------------------------------------------- |
@@ -125,6 +124,8 @@ This process is then repeated a number of times and returns a converged solution
125124
| threshold_to_consider | double | Default 0.4. Distance between robot and goal above which path angle cost stops being considered |
126125
| offset_from_furthest | int | Default 4. Number of path points after furthest one any trajectory achieves to compute path angle relative to. |
127126
| max_angle_to_furthest | double | Default 1.2. Angular distance between robot and goal above which path angle cost starts being considered |
127+
| forward_preference | bool | Default true. Whether or not your robot has a preference for which way is forward in motion. Different from if reversing is generally allowed, but if you robot contains *no* particular preference one way or another. |
128+
128129

129130
#### Path Follow Critic
130131
| Parameter | Type | Definition |
@@ -227,6 +228,7 @@ controller_server:
227228
offset_from_furthest: 4
228229
threshold_to_consider: 0.40
229230
max_angle_to_furthest: 1.0
231+
forward_preference: true
230232
# TwirlingCritic:
231233
# enabled: true
232234
# twirling_cost_power: 1

nav2_mppi_controller/include/nav2_mppi_controller/critics/path_angle_critic.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -48,6 +48,8 @@ class PathAngleCritic : public CriticFunction
4848
float threshold_to_consider_{0};
4949

5050
size_t offset_from_furthest_{0};
51+
bool reversing_allowed_{true};
52+
bool forward_preference_{true};
5153

5254
unsigned int power_{0};
5355
float weight_{0};

nav2_mppi_controller/include/nav2_mppi_controller/tools/utils.hpp

Lines changed: 11 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -416,15 +416,25 @@ inline void setPathCostsIfNotSet(
416416
* @param pose pose
417417
* @param point_x Point to find angle relative to X axis
418418
* @param point_y Point to find angle relative to Y axis
419+
* @param forward_preference If reversing direction is valid
419420
* @return Angle between two points
420421
*/
421-
inline double posePointAngle(const geometry_msgs::msg::Pose & pose, double point_x, double point_y)
422+
inline double posePointAngle(
423+
const geometry_msgs::msg::Pose & pose, double point_x, double point_y, bool forward_preference)
422424
{
423425
double pose_x = pose.position.x;
424426
double pose_y = pose.position.y;
425427
double pose_yaw = tf2::getYaw(pose.orientation);
426428

427429
double yaw = atan2(point_y - pose_y, point_x - pose_x);
430+
431+
// If no preference for forward, return smallest angle either in heading or 180 of heading
432+
if (!forward_preference) {
433+
return std::min(
434+
abs(angles::shortest_angular_distance(yaw, pose_yaw)),
435+
abs(angles::shortest_angular_distance(yaw, pose_yaw + M_PI)));
436+
}
437+
428438
return abs(angles::shortest_angular_distance(yaw, pose_yaw));
429439
}
430440

nav2_mppi_controller/src/critics/constraint_critic.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -28,15 +28,14 @@ void ConstraintCritic::initialize()
2828
logger_, "ConstraintCritic instantiated with %d power and %f weight.",
2929
power_, weight_);
3030

31-
float vx_max, vy_max, vx_min, vy_min;
31+
float vx_max, vy_max, vx_min;
3232
getParentParam(vx_max, "vx_max", 0.5);
3333
getParentParam(vy_max, "vy_max", 0.0);
3434
getParentParam(vx_min, "vx_min", -0.35);
35-
getParentParam(vy_min, "vy_min", 0.0);
3635

3736
const float min_sgn = vx_min > 0.0 ? 1.0 : -1.0;
3837
max_vel_ = std::sqrt(vx_max * vx_max + vy_max * vy_max);
39-
min_vel_ = min_sgn * std::sqrt(vx_min * vx_min + vy_min * vy_min);
38+
min_vel_ = min_sgn * std::sqrt(vx_min * vx_min + vy_max * vy_max);
4039
}
4140

4241
void ConstraintCritic::score(CriticData & data)

nav2_mppi_controller/src/critics/path_angle_critic.cpp

Lines changed: 32 additions & 6 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.
@@ -21,6 +22,15 @@ namespace mppi::critics
2122

2223
void PathAngleCritic::initialize()
2324
{
25+
auto getParentParam = parameters_handler_->getParamGetter(parent_name_);
26+
float vx_min;
27+
getParentParam(vx_min, "vx_min", -0.35);
28+
if (fabs(vx_min) < 1e-6) { // zero
29+
reversing_allowed_ = false;
30+
} else if (vx_min < 0.0) { // reversing possible
31+
reversing_allowed_ = true;
32+
}
33+
2434
auto getParam = parameters_handler_->getParamGetter(name_);
2535
getParam(offset_from_furthest_, "offset_from_furthest", 4);
2636
getParam(power_, "cost_power", 1);
@@ -31,12 +41,18 @@ void PathAngleCritic::initialize()
3141
getParam(
3242
max_angle_to_furthest_,
3343
"max_angle_to_furthest", 1.2);
44+
getParam(
45+
forward_preference_,
46+
"forward_preference", true);
3447

48+
if (!reversing_allowed_) {
49+
forward_preference_ = true;
50+
}
3551

3652
RCLCPP_INFO(
3753
logger_,
38-
"PathAngleCritic instantiated with %d power and %f weight.",
39-
power_, weight_);
54+
"PathAngleCritic instantiated with %d power and %f weight. Reversing %s",
55+
power_, weight_, reversing_allowed_ ? "allowed." : "not allowed.");
4056
}
4157

4258
void PathAngleCritic::score(CriticData & data)
@@ -58,17 +74,27 @@ void PathAngleCritic::score(CriticData & data)
5874
const float goal_x = xt::view(data.path.x, offseted_idx);
5975
const float goal_y = xt::view(data.path.y, offseted_idx);
6076

61-
if (utils::posePointAngle(data.state.pose.pose, goal_x, goal_y) < max_angle_to_furthest_) {
77+
if (utils::posePointAngle(
78+
data.state.pose.pose, goal_x, goal_y, forward_preference_) < max_angle_to_furthest_)
79+
{
6280
return;
6381
}
6482

65-
const auto yaws_between_points = xt::atan2(
83+
auto yaws_between_points = xt::atan2(
6684
goal_y - data.trajectories.y,
6785
goal_x - data.trajectories.x);
68-
const auto yaws =
86+
87+
auto yaws =
6988
xt::abs(utils::shortest_angular_distance(data.trajectories.yaws, yaws_between_points));
7089

71-
data.costs += xt::pow(xt::mean(yaws, {1}, immediate) * weight_, power_);
90+
if (reversing_allowed_ && !forward_preference_) {
91+
data.costs += xt::pow(
92+
xt::mean(
93+
xt::where(yaws < M_PI_2, yaws, utils::normalize_angles(yaws + M_PI)),
94+
{1}, immediate) * weight_, power_);
95+
} else {
96+
data.costs += xt::pow(xt::mean(yaws, {1}, immediate) * weight_, power_);
97+
}
7298
}
7399

74100
} // namespace mppi::critics

nav2_mppi_controller/test/utils_test.cpp

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -195,7 +195,14 @@ TEST(UtilsTests, AnglesTests)
195195
pose.position.y = 0.0;
196196
pose.orientation.w = 1.0;
197197
double point_x = 1.0, point_y = 0.0;
198-
EXPECT_NEAR(posePointAngle(pose, point_x, point_y), 0.0, 1e-6);
198+
bool forward_preference = true;
199+
EXPECT_NEAR(posePointAngle(pose, point_x, point_y, forward_preference), 0.0, 1e-6);
200+
forward_preference = false;
201+
EXPECT_NEAR(posePointAngle(pose, point_x, point_y, forward_preference), 0.0, 1e-6);
202+
point_x = -1.0;
203+
EXPECT_NEAR(posePointAngle(pose, point_x, point_y, forward_preference), 0.0, 1e-6);
204+
forward_preference = true;
205+
EXPECT_NEAR(posePointAngle(pose, point_x, point_y, forward_preference), M_PI, 1e-6);
199206
}
200207

201208
TEST(UtilsTests, FurthestAndClosestReachedPoint)

0 commit comments

Comments
 (0)