Skip to content

Commit 5efbe9f

Browse files
committed
Enable multiple MPPI path angle modes depending on preferences in behavior (#3650)
* fixing path angle critic's non-directional bias * adding reformat * handle linting * add utility unit tests * adding unit tests for path angle
1 parent 51920ba commit 5efbe9f

File tree

6 files changed

+202
-30
lines changed

6 files changed

+202
-30
lines changed

nav2_mppi_controller/README.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -120,7 +120,7 @@ This process is then repeated a number of times and returns a converged solution
120120
| threshold_to_consider | double | Default 0.5. Distance between robot and goal above which path angle cost stops being considered |
121121
| offset_from_furthest | int | Default 4. Number of path points after furthest one any trajectory achieves to compute path angle relative to. |
122122
| max_angle_to_furthest | double | Default 1.2. Angular distance between robot and goal above which path angle cost starts being considered |
123-
| 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. |
123+
| mode | int | Default 0 (Forward Preference). Enum type for mode of operations for the path angle critic depending on path input types and behavioral desires. 0: Forward Preference, penalizes high path angles relative to the robot's orientation to incentivize turning towards the path. 1: No directional preference, penalizes high path angles relative to the robot's orientation or mirrored orientation (e.g. reverse), which ever is less, when a particular direction of travel is not preferable. 2: Consider feasible path orientation, when using a feasible path whereas the path points have orientation information (e.g. Smac Planners), consider the path's requested direction of travel to penalize path angles such that the robot will follow the path in the requested direction. |
124124

125125

126126
#### Path Follow Critic

nav2_mppi_controller/include/nav2_mppi_controller/critics/path_angle_critic.hpp

Lines changed: 29 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -15,13 +15,41 @@
1515
#ifndef NAV2_MPPI_CONTROLLER__CRITICS__PATH_ANGLE_CRITIC_HPP_
1616
#define NAV2_MPPI_CONTROLLER__CRITICS__PATH_ANGLE_CRITIC_HPP_
1717

18+
#include <string>
1819
#include "nav2_mppi_controller/critic_function.hpp"
1920
#include "nav2_mppi_controller/models/state.hpp"
2021
#include "nav2_mppi_controller/tools/utils.hpp"
22+
#include "nav2_core/controller_exceptions.hpp"
2123

2224
namespace mppi::critics
2325
{
2426

27+
/**
28+
* @brief Enum type for different modes of operation
29+
*/
30+
enum class PathAngleMode
31+
{
32+
FORWARD_PREFERENCE = 0,
33+
NO_DIRECTIONAL_PREFERENCE = 1,
34+
CONSIDER_FEASIBLE_PATH_ORIENTATIONS = 2
35+
};
36+
37+
/**
38+
* @brief Method to convert mode enum to string for printing
39+
*/
40+
std::string modeToStr(const PathAngleMode & mode)
41+
{
42+
if (mode == PathAngleMode::FORWARD_PREFERENCE) {
43+
return "Forward Preference";
44+
} else if (mode == PathAngleMode::CONSIDER_FEASIBLE_PATH_ORIENTATIONS) {
45+
return "Consider Feasible Path Orientations";
46+
} else if (mode == PathAngleMode::NO_DIRECTIONAL_PREFERENCE) {
47+
return "No Directional Preference";
48+
} else {
49+
return "Invalid mode!";
50+
}
51+
}
52+
2553
/**
2654
* @class mppi::critics::ConstraintCritic
2755
* @brief Critic objective function for aligning to path in cases of extreme misalignment
@@ -49,7 +77,7 @@ class PathAngleCritic : public CriticFunction
4977

5078
size_t offset_from_furthest_{0};
5179
bool reversing_allowed_{true};
52-
bool forward_preference_{true};
80+
PathAngleMode mode_{0};
5381

5482
unsigned int power_{0};
5583
float weight_{0};

nav2_mppi_controller/include/nav2_mppi_controller/tools/utils.hpp

Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -438,6 +438,31 @@ inline double posePointAngle(
438438
return abs(angles::shortest_angular_distance(yaw, pose_yaw));
439439
}
440440

441+
/**
442+
* @brief evaluate angle from pose (have angle) to point (no angle)
443+
* @param pose pose
444+
* @param point_x Point to find angle relative to X axis
445+
* @param point_y Point to find angle relative to Y axis
446+
* @param point_yaw Yaw of the point to consider along Z axis
447+
* @return Angle between two points
448+
*/
449+
inline double posePointAngle(
450+
const geometry_msgs::msg::Pose & pose,
451+
double point_x, double point_y, double point_yaw)
452+
{
453+
double pose_x = pose.position.x;
454+
double pose_y = pose.position.y;
455+
double pose_yaw = tf2::getYaw(pose.orientation);
456+
457+
double yaw = atan2(point_y - pose_y, point_x - pose_x);
458+
459+
if (abs(angles::shortest_angular_distance(yaw, point_yaw)) > M_PI_2) {
460+
yaw = angles::normalize_angle(yaw + M_PI);
461+
}
462+
463+
return abs(angles::shortest_angular_distance(yaw, pose_yaw));
464+
}
465+
441466
/**
442467
* @brief Apply Savisky-Golay filter to optimal trajectory
443468
* @param control_sequence Sequence to apply filter to

nav2_mppi_controller/src/critics/path_angle_critic.cpp

Lines changed: 62 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,8 @@
2020
namespace mppi::critics
2121
{
2222

23+
using xt::evaluation_strategy::immediate;
24+
2325
void PathAngleCritic::initialize()
2426
{
2527
auto getParentParam = parameters_handler_->getParamGetter(parent_name_);
@@ -41,43 +43,59 @@ void PathAngleCritic::initialize()
4143
getParam(
4244
max_angle_to_furthest_,
4345
"max_angle_to_furthest", 1.2);
44-
getParam(
45-
forward_preference_,
46-
"forward_preference", true);
4746

48-
if (!reversing_allowed_) {
49-
forward_preference_ = true;
47+
int mode = 0;
48+
getParam(mode, "mode", mode);
49+
mode_ = static_cast<PathAngleMode>(mode);
50+
if (!reversing_allowed_ && mode_ == PathAngleMode::NO_DIRECTIONAL_PREFERENCE) {
51+
mode_ = PathAngleMode::FORWARD_PREFERENCE;
52+
RCLCPP_WARN(
53+
logger_,
54+
"Path angle mode set to no directional preference, but controller's settings "
55+
"don't allow for reversing! Setting mode to forward preference.");
5056
}
5157

5258
RCLCPP_INFO(
5359
logger_,
54-
"PathAngleCritic instantiated with %d power and %f weight. Reversing %s",
55-
power_, weight_, reversing_allowed_ ? "allowed." : "not allowed.");
60+
"PathAngleCritic instantiated with %d power and %f weight. Mode set to: %s",
61+
power_, weight_, modeToStr(mode_).c_str());
5662
}
5763

5864
void PathAngleCritic::score(CriticData & data)
5965
{
60-
using xt::evaluation_strategy::immediate;
61-
if (!enabled_) {
62-
return;
63-
}
64-
65-
if (utils::withinPositionGoalTolerance(threshold_to_consider_, data.state.pose.pose, data.path)) {
66+
if (!enabled_ ||
67+
utils::withinPositionGoalTolerance(threshold_to_consider_, data.state.pose.pose, data.path))
68+
{
6669
return;
6770
}
6871

6972
utils::setPathFurthestPointIfNotSet(data);
70-
7173
auto offseted_idx = std::min(
7274
*data.furthest_reached_path_point + offset_from_furthest_, data.path.x.shape(0) - 1);
7375

7476
const float goal_x = xt::view(data.path.x, offseted_idx);
7577
const float goal_y = xt::view(data.path.y, offseted_idx);
76-
77-
if (utils::posePointAngle(
78-
data.state.pose.pose, goal_x, goal_y, forward_preference_) < max_angle_to_furthest_)
79-
{
80-
return;
78+
const float goal_yaw = xt::view(data.path.yaws, offseted_idx);
79+
const geometry_msgs::msg::Pose & pose = data.state.pose.pose;
80+
81+
switch (mode_) {
82+
case PathAngleMode::FORWARD_PREFERENCE:
83+
if (utils::posePointAngle(pose, goal_x, goal_y, true) < max_angle_to_furthest_) {
84+
return;
85+
}
86+
break;
87+
case PathAngleMode::NO_DIRECTIONAL_PREFERENCE:
88+
if (utils::posePointAngle(pose, goal_x, goal_y, false) < max_angle_to_furthest_) {
89+
return;
90+
}
91+
break;
92+
case PathAngleMode::CONSIDER_FEASIBLE_PATH_ORIENTATIONS:
93+
if (utils::posePointAngle(pose, goal_x, goal_y, goal_yaw) < max_angle_to_furthest_) {
94+
return;
95+
}
96+
break;
97+
default:
98+
throw nav2_core::ControllerException("Invalid path angle mode!");
8199
}
82100

83101
auto yaws_between_points = xt::atan2(
@@ -87,14 +105,31 @@ void PathAngleCritic::score(CriticData & data)
87105
auto yaws =
88106
xt::abs(utils::shortest_angular_distance(data.trajectories.yaws, yaws_between_points));
89107

90-
if (reversing_allowed_ && !forward_preference_) {
91-
const auto yaws_between_points_corrected = xt::where(
92-
yaws < M_PI_2, yaws_between_points, utils::normalize_angles(yaws_between_points + M_PI));
93-
const auto corrected_yaws = xt::abs(
94-
utils::shortest_angular_distance(data.trajectories.yaws, yaws_between_points_corrected));
95-
data.costs += xt::pow(xt::mean(corrected_yaws, {1}, immediate) * weight_, power_);
96-
} else {
97-
data.costs += xt::pow(xt::mean(yaws, {1}, immediate) * weight_, power_);
108+
switch (mode_) {
109+
case PathAngleMode::FORWARD_PREFERENCE:
110+
{
111+
data.costs += xt::pow(xt::mean(yaws, {1}, immediate) * weight_, power_);
112+
return;
113+
}
114+
case PathAngleMode::NO_DIRECTIONAL_PREFERENCE:
115+
{
116+
const auto yaws_between_points_corrected = xt::where(
117+
yaws < M_PI_2, yaws_between_points, utils::normalize_angles(yaws_between_points + M_PI));
118+
const auto corrected_yaws = xt::abs(
119+
utils::shortest_angular_distance(data.trajectories.yaws, yaws_between_points_corrected));
120+
data.costs += xt::pow(xt::mean(corrected_yaws, {1}, immediate) * weight_, power_);
121+
return;
122+
}
123+
case PathAngleMode::CONSIDER_FEASIBLE_PATH_ORIENTATIONS:
124+
{
125+
const auto yaws_between_points_corrected = xt::where(
126+
xt::abs(utils::shortest_angular_distance(yaws_between_points, goal_yaw)) < M_PI_2,
127+
yaws_between_points, utils::normalize_angles(yaws_between_points + M_PI));
128+
const auto corrected_yaws = xt::abs(
129+
utils::shortest_angular_distance(data.trajectories.yaws, yaws_between_points_corrected));
130+
data.costs += xt::pow(xt::mean(corrected_yaws, {1}, immediate) * weight_, power_);
131+
return;
132+
}
98133
}
99134
}
100135

nav2_mppi_controller/test/critics_tests.cpp

Lines changed: 74 additions & 1 deletion
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.
@@ -39,6 +40,20 @@ using namespace mppi::critics; // NOLINT
3940
using namespace mppi::utils; // NOLINT
4041
using xt::evaluation_strategy::immediate;
4142

43+
class PathAngleCriticWrapper : public PathAngleCritic
44+
{
45+
public:
46+
PathAngleCriticWrapper()
47+
: PathAngleCritic()
48+
{
49+
}
50+
51+
void setMode(int mode)
52+
{
53+
mode_ = static_cast<PathAngleMode>(mode);
54+
}
55+
};
56+
4257
TEST(CriticTests, ConstraintsCritic)
4358
{
4459
// Standard preamble
@@ -239,7 +254,7 @@ TEST(CriticTests, PathAngleCritic)
239254
// Initialization testing
240255

241256
// Make sure initializes correctly
242-
PathAngleCritic critic;
257+
PathAngleCriticWrapper critic;
243258
critic.on_configure(node, "mppi", "critic", costmap_ros, &param_handler);
244259
EXPECT_EQ(critic.getName(), "critic");
245260

@@ -267,6 +282,64 @@ TEST(CriticTests, PathAngleCritic)
267282
critic.score(data);
268283
EXPECT_GT(xt::sum(costs, immediate)(), 0.0);
269284
EXPECT_NEAR(costs(0), 3.6315, 1e-2); // atan2(4,-1) [1.81] * 2.0 weight
285+
286+
// Set mode to no directional preferences + reset costs
287+
critic.setMode(1);
288+
costs = xt::zeros<float>({1000});
289+
290+
// provide state pose and path close but outside of tol. with more than PI/2 angular diff.
291+
path.x(6) = 1.0; // angle between path point and pose < max_angle_to_furthest_
292+
path.y(6) = 0.0;
293+
critic.score(data);
294+
EXPECT_NEAR(xt::sum(costs, immediate)(), 0.0, 1e-6);
295+
296+
// provide state pose and path close but outside of tol. with more than PI/2 angular diff.
297+
path.x(6) = -1.0; // angle between path pt and pose < max_angle_to_furthest_ IF non-directional
298+
path.y(6) = 0.0;
299+
critic.score(data);
300+
EXPECT_NEAR(xt::sum(costs, immediate)(), 0.0, 1e-6);
301+
302+
// provide state pose and path close but outside of tol. with more than PI/2 angular diff.
303+
path.x(6) = -1.0; // angle between path point and pose < max_angle_to_furthest_
304+
path.y(6) = 4.0;
305+
critic.score(data);
306+
EXPECT_GT(xt::sum(costs, immediate)(), 0.0);
307+
// should use reverse orientation as the closer angle in no dir preference mode
308+
EXPECT_NEAR(costs(0), 2.6516, 1e-2);
309+
310+
// Set mode to consider path directionality + reset costs
311+
critic.setMode(2);
312+
costs = xt::zeros<float>({1000});
313+
314+
// provide state pose and path close but outside of tol. with more than PI/2 angular diff.
315+
path.x(6) = 1.0; // angle between path point and pose < max_angle_to_furthest_
316+
path.y(6) = 0.0;
317+
critic.score(data);
318+
EXPECT_NEAR(xt::sum(costs, immediate)(), 0.0, 1e-6);
319+
320+
// provide state pose and path close but outside of tol. with more than PI/2 angular diff.
321+
path.x(6) = -1.0; // angle between path pt and pose < max_angle_to_furthest_ IF non-directional
322+
path.y(6) = 0.0;
323+
critic.score(data);
324+
EXPECT_NEAR(xt::sum(costs, immediate)(), 0.0, 1e-6);
325+
326+
// provide state pose and path close but outside of tol. with more than PI/2 angular diff.
327+
path.x(6) = -1.0; // angle between path point and pose < max_angle_to_furthest_
328+
path.y(6) = 4.0;
329+
critic.score(data);
330+
EXPECT_GT(xt::sum(costs, immediate)(), 0.0);
331+
// should use reverse orientation as the closer angle in no dir preference mode
332+
EXPECT_NEAR(costs(0), 2.6516, 1e-2);
333+
334+
PathAngleMode mode;
335+
mode = PathAngleMode::FORWARD_PREFERENCE;
336+
EXPECT_EQ(modeToStr(mode), std::string("Forward Preference"));
337+
mode = PathAngleMode::CONSIDER_FEASIBLE_PATH_ORIENTATIONS;
338+
EXPECT_EQ(modeToStr(mode), std::string("Consider Feasible Path Orientations"));
339+
mode = PathAngleMode::NO_DIRECTIONAL_PREFERENCE;
340+
EXPECT_EQ(modeToStr(mode), std::string("No Directional Preference"));
341+
mode = static_cast<PathAngleMode>(4);
342+
EXPECT_EQ(modeToStr(mode), std::string("Invalid mode!"));
270343
}
271344

272345
TEST(CriticTests, PreferForwardCritic)

nav2_mppi_controller/test/utils_test.cpp

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -203,6 +203,17 @@ TEST(UtilsTests, AnglesTests)
203203
EXPECT_NEAR(posePointAngle(pose, point_x, point_y, forward_preference), 0.0, 1e-6);
204204
forward_preference = true;
205205
EXPECT_NEAR(posePointAngle(pose, point_x, point_y, forward_preference), M_PI, 1e-6);
206+
207+
// Test point-pose angle with goal yaws
208+
point_x = 1.0;
209+
double point_yaw = 0.0;
210+
EXPECT_NEAR(posePointAngle(pose, point_x, point_y, point_yaw), 0.0, 1e-6);
211+
point_yaw = M_PI;
212+
EXPECT_NEAR(posePointAngle(pose, point_x, point_y, point_yaw), M_PI, 1e-6);
213+
point_yaw = 0.1;
214+
EXPECT_NEAR(posePointAngle(pose, point_x, point_y, point_yaw), 0.0, 1e-3);
215+
point_yaw = 3.04159;
216+
EXPECT_NEAR(posePointAngle(pose, point_x, point_y, point_yaw), M_PI, 1e-3);
206217
}
207218

208219
TEST(UtilsTests, FurthestAndClosestReachedPoint)

0 commit comments

Comments
 (0)