Skip to content

Commit 262a242

Browse files
redvinaaRBT22
authored andcommitted
Mppi goal to critic (ros-navigation#4822)
* Add goal pose to CriticData Signed-off-by: redvinaa <[email protected]> * Pass goal pose directly to withinPositionGoalTolerance Signed-off-by: redvinaa <[email protected]> * Fix condition not Signed-off-by: redvinaa <[email protected]> * Add goal positions to tests Signed-off-by: redvinaa <[email protected]> * Use plan stamp Signed-off-by: redvinaa <[email protected]> * Use float instead of auto Signed-off-by: redvinaa <[email protected]> * Throw nav2_core exceptions Signed-off-by: redvinaa <[email protected]> * Set pose frame id in test Signed-off-by: redvinaa <[email protected]> * Fix frame id in test vol 2 Signed-off-by: redvinaa <[email protected]> --------- Signed-off-by: redvinaa <[email protected]> Signed-off-by: RBT22 <[email protected]>
1 parent bc9f2bc commit 262a242

22 files changed

+160
-97
lines changed

nav2_mppi_controller/include/nav2_mppi_controller/critic_data.hpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -38,14 +38,15 @@ namespace mppi
3838

3939
/**
4040
* @struct mppi::CriticData
41-
* @brief Data to pass to critics for scoring, including state, trajectories, path, costs, and
42-
* important parameters to share
41+
* @brief Data to pass to critics for scoring, including state, trajectories,
42+
* pruned path, global goal, costs, and important parameters to share
4343
*/
4444
struct CriticData
4545
{
4646
const models::State & state;
4747
const models::Trajectories & trajectories;
4848
const models::Path & path;
49+
const geometry_msgs::msg::Pose & goal;
4950

5051
xt::xtensor<float, 1> & costs;
5152
float & model_dt;

nav2_mppi_controller/include/nav2_mppi_controller/optimizer.hpp

Lines changed: 7 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -96,7 +96,7 @@ class Optimizer
9696
geometry_msgs::msg::TwistStamped evalControl(
9797
const geometry_msgs::msg::PoseStamped & robot_pose,
9898
const geometry_msgs::msg::Twist & robot_speed, const nav_msgs::msg::Path & plan,
99-
nav2_core::GoalChecker * goal_checker);
99+
const geometry_msgs::msg::Pose & goal, nav2_core::GoalChecker * goal_checker);
100100

101101
/**
102102
* @brief Get the trajectories generated in a cycle for visualization
@@ -138,7 +138,8 @@ class Optimizer
138138
void prepare(
139139
const geometry_msgs::msg::PoseStamped & robot_pose,
140140
const geometry_msgs::msg::Twist & robot_speed,
141-
const nav_msgs::msg::Path & plan, nav2_core::GoalChecker * goal_checker);
141+
const nav_msgs::msg::Path & plan,
142+
const geometry_msgs::msg::Pose & goal, nav2_core::GoalChecker * goal_checker);
142143

143144
/**
144145
* @brief Obtain the main controller's parameters
@@ -256,10 +257,12 @@ class Optimizer
256257
std::array<mppi::models::Control, 4> control_history_;
257258
models::Trajectories generated_trajectories_;
258259
models::Path path_;
260+
geometry_msgs::msg::Pose goal_;
259261
xt::xtensor<float, 1> costs_;
260262

261-
CriticData critics_data_ =
262-
{state_, generated_trajectories_, path_, costs_, settings_.model_dt, false, nullptr, nullptr,
263+
CriticData critics_data_ = {
264+
state_, generated_trajectories_, path_, goal_,
265+
costs_, settings_.model_dt, false, nullptr, nullptr,
263266
std::nullopt, std::nullopt}; /// Caution, keep references
264267

265268
rclcpp::Logger logger_{rclcpp::get_logger("MPPIController")};

nav2_mppi_controller/include/nav2_mppi_controller/tools/path_handler.hpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -90,6 +90,12 @@ class PathHandler
9090
*/
9191
nav_msgs::msg::Path transformPath(const geometry_msgs::msg::PoseStamped & robot_pose);
9292

93+
/**
94+
* @brief Get the global goal pose transformed to the local frame
95+
* @return Transformed goal pose
96+
*/
97+
geometry_msgs::msg::PoseStamped getTransformedGoal();
98+
9399
protected:
94100
/**
95101
* @brief Transform a pose to another frame

nav2_mppi_controller/include/nav2_mppi_controller/tools/utils.hpp

Lines changed: 9 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -204,27 +204,23 @@ inline models::Path toTensor(const nav_msgs::msg::Path & path)
204204
* @brief Check if the robot pose is within the Goal Checker's tolerances to goal
205205
* @param global_checker Pointer to the goal checker
206206
* @param robot Pose of robot
207-
* @param path Path to retrieve goal pose from
207+
* @param goal Goal pose
208208
* @return bool If robot is within goal checker tolerances to the goal
209209
*/
210210
inline bool withinPositionGoalTolerance(
211211
nav2_core::GoalChecker * goal_checker,
212212
const geometry_msgs::msg::Pose & robot,
213-
const models::Path & path)
213+
const geometry_msgs::msg::Pose & goal)
214214
{
215-
const auto goal_idx = path.x.shape(0) - 1;
216-
const auto goal_x = path.x(goal_idx);
217-
const auto goal_y = path.y(goal_idx);
218-
219215
if (goal_checker) {
220216
geometry_msgs::msg::Pose pose_tolerance;
221217
geometry_msgs::msg::Twist velocity_tolerance;
222218
goal_checker->getTolerances(pose_tolerance, velocity_tolerance);
223219

224220
const auto pose_tolerance_sq = pose_tolerance.position.x * pose_tolerance.position.x;
225221

226-
auto dx = robot.position.x - goal_x;
227-
auto dy = robot.position.y - goal_y;
222+
auto dx = robot.position.x - goal.position.x;
223+
auto dy = robot.position.y - goal.position.y;
228224

229225
auto dist_sq = dx * dx + dy * dy;
230226

@@ -240,25 +236,20 @@ inline bool withinPositionGoalTolerance(
240236
* @brief Check if the robot pose is within tolerance to the goal
241237
* @param pose_tolerance Pose tolerance to use
242238
* @param robot Pose of robot
243-
* @param path Path to retrieve goal pose from
239+
* @param goal Goal pose
244240
* @return bool If robot is within tolerance to the goal
245241
*/
246242
inline bool withinPositionGoalTolerance(
247243
float pose_tolerance,
248244
const geometry_msgs::msg::Pose & robot,
249-
const models::Path & path)
245+
const geometry_msgs::msg::Pose & goal)
250246
{
251-
const auto goal_idx = path.x.shape(0) - 1;
252-
const float goal_x = path.x(goal_idx);
253-
const float goal_y = path.y(goal_idx);
247+
const double & dist_sq =
248+
std::pow(goal.position.x - robot.position.x, 2) +
249+
std::pow(goal.position.y - robot.position.y, 2);
254250

255251
const float pose_tolerance_sq = pose_tolerance * pose_tolerance;
256252

257-
const float dx = static_cast<float>(robot.position.x) - goal_x;
258-
const float dy = static_cast<float>(robot.position.y) - goal_y;
259-
260-
float dist_sq = dx * dx + dy * dy;
261-
262253
if (dist_sq < pose_tolerance_sq) {
263254
return true;
264255
}

nav2_mppi_controller/src/controller.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -84,13 +84,15 @@ geometry_msgs::msg::TwistStamped MPPIController::computeVelocityCommands(
8484
#endif
8585

8686
std::lock_guard<std::mutex> param_lock(*parameters_handler_->getLock());
87+
geometry_msgs::msg::Pose goal = path_handler_.getTransformedGoal().pose;
88+
8789
nav_msgs::msg::Path transformed_plan = path_handler_.transformPath(robot_pose);
8890

8991
nav2_costmap_2d::Costmap2D * costmap = costmap_ros_->getCostmap();
9092
std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> costmap_lock(*(costmap->getMutex()));
9193

9294
geometry_msgs::msg::TwistStamped cmd =
93-
optimizer_.evalControl(robot_pose, robot_speed, transformed_plan, goal_checker);
95+
optimizer_.evalControl(robot_pose, robot_speed, transformed_plan, goal, goal_checker);
9496

9597
#ifdef BENCHMARK_TESTING
9698
auto end = std::chrono::system_clock::now();

nav2_mppi_controller/src/critics/cost_critic.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -119,7 +119,7 @@ void CostCritic::score(CriticData & data)
119119

120120
// If near the goal, don't apply the preferential term since the goal is near obstacles
121121
bool near_goal = false;
122-
if (utils::withinPositionGoalTolerance(near_goal_distance_, data.state.pose.pose, data.path)) {
122+
if (utils::withinPositionGoalTolerance(near_goal_distance_, data.state.pose.pose, data.goal)) {
123123
near_goal = true;
124124
}
125125

nav2_mppi_controller/src/critics/goal_angle_critic.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,7 @@ void GoalAngleCritic::initialize()
3636
void GoalAngleCritic::score(CriticData & data)
3737
{
3838
if (!enabled_ || !utils::withinPositionGoalTolerance(
39-
threshold_to_consider_, data.state.pose.pose, data.path))
39+
threshold_to_consider_, data.state.pose.pose, data.goal))
4040
{
4141
return;
4242
}

nav2_mppi_controller/src/critics/goal_critic.cpp

Lines changed: 3 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -36,15 +36,13 @@ void GoalCritic::initialize()
3636
void GoalCritic::score(CriticData & data)
3737
{
3838
if (!enabled_ || !utils::withinPositionGoalTolerance(
39-
threshold_to_consider_, data.state.pose.pose, data.path))
39+
threshold_to_consider_, data.state.pose.pose, data.goal))
4040
{
4141
return;
4242
}
4343

44-
const auto goal_idx = data.path.x.shape(0) - 1;
45-
46-
const auto goal_x = data.path.x(goal_idx);
47-
const auto goal_y = data.path.y(goal_idx);
44+
const auto & goal_x = data.goal.position.x;
45+
const auto & goal_y = data.goal.position.y;
4846

4947
const auto traj_x = xt::view(data.trajectories.x, xt::all(), xt::all());
5048
const auto traj_y = xt::view(data.trajectories.y, xt::all(), xt::all());

nav2_mppi_controller/src/critics/obstacles_critic.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -116,7 +116,7 @@ void ObstaclesCritic::score(CriticData & data)
116116

117117
// If near the goal, don't apply the preferential term since the goal is near obstacles
118118
bool near_goal = false;
119-
if (utils::withinPositionGoalTolerance(near_goal_distance_, data.state.pose.pose, data.path)) {
119+
if (utils::withinPositionGoalTolerance(near_goal_distance_, data.state.pose.pose, data.goal)) {
120120
near_goal = true;
121121
}
122122

nav2_mppi_controller/src/critics/path_align_critic.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -43,8 +43,8 @@ void PathAlignCritic::initialize()
4343
void PathAlignCritic::score(CriticData & data)
4444
{
4545
// Don't apply close to goal, let the goal critics take over
46-
if (!enabled_ ||
47-
utils::withinPositionGoalTolerance(threshold_to_consider_, data.state.pose.pose, data.path))
46+
if (!enabled_ || utils::withinPositionGoalTolerance(
47+
threshold_to_consider_, data.state.pose.pose, data.goal))
4848
{
4949
return;
5050
}

0 commit comments

Comments
 (0)