Skip to content

Commit 1c56c7a

Browse files
Publish optimal trajectory as a Path message
Signed-off-by: Alyssa Agnissan <alyssa.agnissan@quantillion.io>
1 parent f73fa24 commit 1c56c7a

File tree

2 files changed

+46
-0
lines changed

2 files changed

+46
-0
lines changed

nav2_mppi_controller/include/nav2_mppi_controller/controller.hpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -108,6 +108,12 @@ class MPPIController : public nav2_core::Controller
108108
*/
109109
void visualize(nav_msgs::msg::Path transformed_plan);
110110

111+
/**
112+
* @brief Publish the optimal trajectory in the form of a path message
113+
* @param trajectory Optimal trajectory
114+
*/
115+
void publish_optimal_path(const xt::xtensor<float, 2> & optimal_traj);
116+
111117
std::string name_;
112118
rclcpp_lifecycle::LifecycleNode::WeakPtr parent_;
113119
rclcpp::Logger logger_{rclcpp::get_logger("MPPIController")};
@@ -119,6 +125,8 @@ class MPPIController : public nav2_core::Controller
119125
PathHandler path_handler_;
120126
TrajectoryVisualizer trajectory_visualizer_;
121127

128+
rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>::SharedPtr optimal_path_pub_;
129+
122130
bool visualize_;
123131
};
124132

nav2_mppi_controller/src/controller.cpp

Lines changed: 38 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,8 @@ void MPPIController::configure(
4545
parent_, name_,
4646
costmap_ros_->getGlobalFrameID(), parameters_handler_.get());
4747

48+
optimal_path_pub_ = node->create_publisher<nav_msgs::msg::Path>("local_plan", 1);
49+
4850
RCLCPP_INFO(logger_, "Configured MPPI Controller: %s", name_.c_str());
4951
}
5052

@@ -60,12 +62,14 @@ void MPPIController::activate()
6062
{
6163
trajectory_visualizer_.on_activate();
6264
parameters_handler_->start();
65+
optimal_path_pub_->on_activate();
6366
RCLCPP_INFO(logger_, "Activated MPPI Controller: %s", name_.c_str());
6467
}
6568

6669
void MPPIController::deactivate()
6770
{
6871
trajectory_visualizer_.on_deactivate();
72+
optimal_path_pub_->on_deactivate();
6973
RCLCPP_INFO(logger_, "Deactivated MPPI Controller: %s", name_.c_str());
7074
}
7175

@@ -98,6 +102,10 @@ geometry_msgs::msg::TwistStamped MPPIController::computeVelocityCommands(
98102
RCLCPP_INFO(logger_, "Control loop execution time: %ld [ms]", duration);
99103
#endif
100104

105+
if (optimal_path_pub_->get_subscription_count() > 0) {
106+
publish_optimal_path(optimizer_.getOptimizedTrajectory());
107+
}
108+
101109
if (visualize_) {
102110
visualize(std::move(transformed_plan));
103111
}
@@ -122,6 +130,36 @@ void MPPIController::setSpeedLimit(const double & speed_limit, const bool & perc
122130
optimizer_.setSpeedLimit(speed_limit, percentage);
123131
}
124132

133+
void MPPIController::publish_optimal_path(const xt::xtensor<float, 2> & optimal_traj)
134+
{
135+
auto & size = optimal_traj.shape()[0];
136+
if (!size) {
137+
return;
138+
}
139+
140+
nav_msgs::msg::Path optimal_path;
141+
optimal_path.header.stamp = clock_->now();
142+
optimal_path.header.frame_id = (costmap_ros_->getGlobalFrameID()).c_str();
143+
144+
for (size_t i = 0; i < size; i++) {
145+
// create new pose for the path
146+
geometry_msgs::msg::PoseStamped pose_stamped;
147+
pose_stamped.header.frame_id = (costmap_ros_->getGlobalFrameID()).c_str();
148+
149+
// position & orientation
150+
pose_stamped.pose = utils::createPose(optimal_traj(i, 0), optimal_traj(i, 1), 0.);
151+
152+
tf2::Quaternion quaternion_tf2;
153+
quaternion_tf2.setRPY(0., 0., optimal_traj(i, 2));
154+
auto quaternion = tf2::toMsg(quaternion_tf2);
155+
pose_stamped.pose.orientation = quaternion;
156+
157+
// add pose to the path
158+
optimal_path.poses.push_back(pose_stamped);
159+
}
160+
optimal_path_pub_->publish(optimal_path);
161+
}
162+
125163
} // namespace nav2_mppi_controller
126164

127165
#include "pluginlib/class_list_macros.hpp"

0 commit comments

Comments
 (0)