@@ -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
6669void 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,11 @@ 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+ {
107+ publish_optimal_path (optimizer_.getOptimizedTrajectory ());
108+ }
109+
101110 if (visualize_) {
102111 visualize (std::move (transformed_plan));
103112 }
@@ -122,6 +131,38 @@ void MPPIController::setSpeedLimit(const double & speed_limit, const bool & perc
122131 optimizer_.setSpeedLimit (speed_limit, percentage);
123132}
124133
134+ void MPPIController::publish_optimal_path (const xt::xtensor<float , 2 >& optimal_traj)
135+ {
136+ auto & size = optimal_traj.shape ()[0 ];
137+ if (!size)
138+ {
139+ return ;
140+ }
141+
142+ nav_msgs::msg::Path optimal_path;
143+ optimal_path.header .stamp = clock_->now ();
144+ optimal_path.header .frame_id = (costmap_ros_->getGlobalFrameID ()).c_str ();
145+
146+ for (size_t i = 0 ; i < size; i++)
147+ {
148+ // create new pose for the path
149+ geometry_msgs::msg::PoseStamped pose_stamped;
150+ pose_stamped.header .frame_id = (costmap_ros_->getGlobalFrameID ()).c_str ();
151+
152+ // position & orientation
153+ pose_stamped.pose = utils::createPose (optimal_traj (i, 0 ), optimal_traj (i, 1 ), 0 .);
154+
155+ tf2::Quaternion quaternion_tf2;
156+ quaternion_tf2.setRPY (0 ., 0 ., optimal_traj (i, 2 ));
157+ auto quaternion = tf2::toMsg (quaternion_tf2);
158+ pose_stamped.pose .orientation = quaternion;
159+
160+ // add pose to the path
161+ optimal_path.poses .push_back (pose_stamped);
162+ }
163+ optimal_path_pub_->publish (optimal_path);
164+ }
165+
125166} // namespace nav2_mppi_controller
126167
127168#include " pluginlib/class_list_macros.hpp"
0 commit comments