16 #include "nav2_mppi_controller/critics/path_angle_critic.hpp"
20 namespace mppi::critics
23 using xt::evaluation_strategy::immediate;
27 auto getParentParam = parameters_handler_->
getParamGetter(parent_name_);
29 getParentParam(vx_min,
"vx_min", -0.35);
30 if (fabs(vx_min) < 1e-6f) {
31 reversing_allowed_ =
false;
32 }
else if (vx_min < 0.0f) {
33 reversing_allowed_ =
true;
37 getParam(offset_from_furthest_,
"offset_from_furthest", 4);
38 getParam(power_,
"cost_power", 1);
39 getParam(weight_,
"cost_weight", 2.2f);
41 threshold_to_consider_,
42 "threshold_to_consider", 0.5f);
44 max_angle_to_furthest_,
45 "max_angle_to_furthest", 0.785398f);
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;
54 "Path angle mode set to no directional preference, but controller's settings "
55 "don't allow for reversing! Setting mode to forward preference.");
60 "PathAngleCritic instantiated with %d power and %f weight. Mode set to: %s",
61 power_, weight_, modeToStr(mode_).c_str());
67 utils::withinPositionGoalTolerance(threshold_to_consider_, data.state.pose.pose, data.goal))
72 utils::setPathFurthestPointIfNotSet(data);
73 auto offseted_idx = std::min(
74 *data.furthest_reached_path_point + offset_from_furthest_, data.path.x.shape(0) - 1);
76 const float goal_x = data.path.x(offseted_idx);
77 const float goal_y = data.path.y(offseted_idx);
78 const float goal_yaw = data.path.yaws(offseted_idx);
79 const geometry_msgs::msg::Pose & pose = data.state.pose.pose;
82 case PathAngleMode::FORWARD_PREFERENCE:
83 if (utils::posePointAngle(pose, goal_x, goal_y,
true) < max_angle_to_furthest_) {
87 case PathAngleMode::NO_DIRECTIONAL_PREFERENCE:
88 if (utils::posePointAngle(pose, goal_x, goal_y,
false) < max_angle_to_furthest_) {
92 case PathAngleMode::CONSIDER_FEASIBLE_PATH_ORIENTATIONS:
93 if (utils::posePointAngle(pose, goal_x, goal_y, goal_yaw) < max_angle_to_furthest_) {
101 auto yaws_between_points = xt::atan2(
102 goal_y - xt::view(data.trajectories.y, xt::all(), -1),
103 goal_x - xt::view(data.trajectories.x, xt::all(), -1));
106 case PathAngleMode::FORWARD_PREFERENCE:
110 utils::shortest_angular_distance(
111 xt::view(data.trajectories.yaws, xt::all(), -1), yaws_between_points));
113 data.costs += xt::pow(std::move(yaws) * weight_, power_);
115 data.costs += std::move(yaws) * weight_;
119 case PathAngleMode::NO_DIRECTIONAL_PREFERENCE:
123 utils::shortest_angular_distance(
124 xt::view(data.trajectories.yaws, xt::all(), -1), yaws_between_points));
125 const auto yaws_between_points_corrected = xt::where(
126 yaws < M_PIF_2, yaws_between_points,
127 utils::normalize_angles(yaws_between_points + M_PIF));
128 const auto corrected_yaws = xt::fabs(
129 utils::shortest_angular_distance(
130 xt::view(data.trajectories.yaws, xt::all(), -1), yaws_between_points_corrected));
132 data.costs += xt::pow(std::move(corrected_yaws) * weight_, power_);
134 data.costs += std::move(corrected_yaws) * weight_;
138 case PathAngleMode::CONSIDER_FEASIBLE_PATH_ORIENTATIONS:
140 const auto yaws_between_points_corrected = xt::where(
141 xt::fabs(utils::shortest_angular_distance(yaws_between_points, goal_yaw)) < M_PIF_2,
142 yaws_between_points, utils::normalize_angles(yaws_between_points + M_PIF));
143 const auto corrected_yaws = xt::fabs(
144 utils::shortest_angular_distance(
145 xt::view(data.trajectories.yaws, xt::all(), -1), yaws_between_points_corrected));
147 data.costs += xt::pow(std::move(corrected_yaws) * weight_, power_);
149 data.costs += std::move(corrected_yaws) * weight_;
158 #include <pluginlib/class_list_macros.hpp>
160 PLUGINLIB_EXPORT_CLASS(
auto getParamGetter(const std::string &ns)
Get an object to retreive parameters.
Abstract critic objective function to score trajectories.
void initialize() override
Initialize critic.
void score(CriticData &data) override
Evaluate cost related to robot orientation at goal pose (considered only if robot near last goal in c...
Data to pass to critics for scoring, including state, trajectories, pruned path, global goal,...