Skip to content

Commit 0d7044d

Browse files
alyquantillionjosephduchesne
authored andcommitted
Publish optimal trajectory as a Path message (ros-navigation#4640)
* Publish optimal trajectory as a Path message Signed-off-by: Alyssa Agnissan <[email protected]> * move publish_optimal_path to TrajectoryVisualizer + minor refactoring Signed-off-by: Alyssa Agnissan <[email protected]> * tests added for optimal path publication Signed-off-by: Alyssa Agnissan <[email protected]> * populate optimal path message in add() Signed-off-by: Alyssa Agnissan <[email protected]> * move path population in add_marker Signed-off-by: Alyssa Agnissan <[email protected]> --------- Signed-off-by: Alyssa Agnissan <[email protected]> Signed-off-by: Joseph Duchesne <[email protected]>
1 parent b0d47af commit 0d7044d

File tree

5 files changed

+103
-8
lines changed

5 files changed

+103
-8
lines changed

nav2_mppi_controller/include/nav2_mppi_controller/controller.hpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -106,7 +106,9 @@ class MPPIController : public nav2_core::Controller
106106
* @brief Visualize trajectories
107107
* @param transformed_plan Transformed input plan
108108
*/
109-
void visualize(nav_msgs::msg::Path transformed_plan);
109+
void visualize(
110+
nav_msgs::msg::Path transformed_plan,
111+
const builtin_interfaces::msg::Time & cmd_stamp);
110112

111113
std::string name_;
112114
rclcpp_lifecycle::LifecycleNode::WeakPtr parent_;

nav2_mppi_controller/include/nav2_mppi_controller/tools/trajectory_visualizer.hpp

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -79,7 +79,9 @@ class TrajectoryVisualizer
7979
* @brief Add an optimal trajectory to visualize
8080
* @param trajectory Optimal trajectory
8181
*/
82-
void add(const xt::xtensor<float, 2> & trajectory, const std::string & marker_namespace);
82+
void add(
83+
const xt::xtensor<float, 2> & trajectory, const std::string & marker_namespace,
84+
const builtin_interfaces::msg::Time & cmd_stamp);
8385

8486
/**
8587
* @brief Add candidate trajectories to visualize
@@ -103,7 +105,9 @@ class TrajectoryVisualizer
103105
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>>
104106
trajectories_publisher_;
105107
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> transformed_path_pub_;
108+
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> optimal_path_pub_;
106109

110+
std::unique_ptr<nav_msgs::msg::Path> optimal_path_;
107111
std::unique_ptr<visualization_msgs::msg::MarkerArray> points_;
108112
int marker_id_ = 0;
109113

nav2_mppi_controller/src/controller.cpp

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -99,16 +99,18 @@ geometry_msgs::msg::TwistStamped MPPIController::computeVelocityCommands(
9999
#endif
100100

101101
if (visualize_) {
102-
visualize(std::move(transformed_plan));
102+
visualize(std::move(transformed_plan), cmd.header.stamp);
103103
}
104104

105105
return cmd;
106106
}
107107

108-
void MPPIController::visualize(nav_msgs::msg::Path transformed_plan)
108+
void MPPIController::visualize(
109+
nav_msgs::msg::Path transformed_plan,
110+
const builtin_interfaces::msg::Time & cmd_stamp)
109111
{
110112
trajectory_visualizer_.add(optimizer_.getGeneratedTrajectories(), "Candidate Trajectories");
111-
trajectory_visualizer_.add(optimizer_.getOptimizedTrajectory(), "Optimal Trajectory");
113+
trajectory_visualizer_.add(optimizer_.getOptimizedTrajectory(), "Optimal Trajectory", cmd_stamp);
112114
trajectory_visualizer_.visualize(std::move(transformed_plan));
113115
}
114116

nav2_mppi_controller/src/trajectory_visualizer.cpp

Lines changed: 25 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@ void TrajectoryVisualizer::on_configure(
2828
trajectories_publisher_ =
2929
node->create_publisher<visualization_msgs::msg::MarkerArray>("/trajectories", 1);
3030
transformed_path_pub_ = node->create_publisher<nav_msgs::msg::Path>("transformed_global_plan", 1);
31+
optimal_path_pub_ = node->create_publisher<nav_msgs::msg::Path>("optimal_trajectory", 1);
3132
parameters_handler_ = parameters_handler;
3233

3334
auto getParam = parameters_handler->getParamGetter(name + ".TrajectoryVisualizer");
@@ -42,22 +43,27 @@ void TrajectoryVisualizer::on_cleanup()
4243
{
4344
trajectories_publisher_.reset();
4445
transformed_path_pub_.reset();
46+
optimal_path_pub_.reset();
4547
}
4648

4749
void TrajectoryVisualizer::on_activate()
4850
{
4951
trajectories_publisher_->on_activate();
5052
transformed_path_pub_->on_activate();
53+
optimal_path_pub_->on_activate();
5154
}
5255

5356
void TrajectoryVisualizer::on_deactivate()
5457
{
5558
trajectories_publisher_->on_deactivate();
5659
transformed_path_pub_->on_deactivate();
60+
optimal_path_pub_->on_deactivate();
5761
}
5862

5963
void TrajectoryVisualizer::add(
60-
const xt::xtensor<float, 2> & trajectory, const std::string & marker_namespace)
64+
const xt::xtensor<float, 2> & trajectory,
65+
const std::string & marker_namespace,
66+
const builtin_interfaces::msg::Time & cmd_stamp)
6167
{
6268
auto & size = trajectory.shape()[0];
6369
if (!size) {
@@ -76,8 +82,21 @@ void TrajectoryVisualizer::add(
7682
auto marker = utils::createMarker(
7783
marker_id_++, pose, scale, color, frame_id_, marker_namespace);
7884
points_->markers.push_back(marker);
85+
86+
// populate optimal path
87+
geometry_msgs::msg::PoseStamped pose_stamped;
88+
pose_stamped.header.frame_id = frame_id_;
89+
pose_stamped.pose = pose;
90+
91+
tf2::Quaternion quaternion_tf2;
92+
quaternion_tf2.setRPY(0., 0., trajectory(i, 2));
93+
pose_stamped.pose.orientation = tf2::toMsg(quaternion_tf2);
94+
95+
optimal_path_->poses.push_back(pose_stamped);
7996
};
8097

98+
optimal_path_->header.stamp = cmd_stamp;
99+
optimal_path_->header.frame_id = frame_id_;
81100
for (size_t i = 0; i < size; i++) {
82101
add_marker(i);
83102
}
@@ -111,6 +130,7 @@ void TrajectoryVisualizer::reset()
111130
{
112131
marker_id_ = 0;
113132
points_ = std::make_unique<visualization_msgs::msg::MarkerArray>();
133+
optimal_path_ = std::make_unique<nav_msgs::msg::Path>();
114134
}
115135

116136
void TrajectoryVisualizer::visualize(const nav_msgs::msg::Path & plan)
@@ -119,6 +139,10 @@ void TrajectoryVisualizer::visualize(const nav_msgs::msg::Path & plan)
119139
trajectories_publisher_->publish(std::move(points_));
120140
}
121141

142+
if (optimal_path_pub_->get_subscription_count() > 0) {
143+
optimal_path_pub_->publish(std::move(optimal_path_));
144+
}
145+
122146
reset();
123147

124148
if (transformed_path_pub_->get_subscription_count() > 0) {

nav2_mppi_controller/test/trajectory_visualizer_tests.cpp

Lines changed: 65 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -81,7 +81,8 @@ TEST(TrajectoryVisualizerTests, VisOptimalTrajectory)
8181
TrajectoryVisualizer vis;
8282
vis.on_configure(node, "my_name", "fkmap", parameters_handler.get());
8383
vis.on_activate();
84-
vis.add(optimal_trajectory, "Optimal Trajectory");
84+
builtin_interfaces::msg::Time bogus_stamp;
85+
vis.add(optimal_trajectory, "Optimal Trajectory", bogus_stamp);
8586
nav_msgs::msg::Path bogus_path;
8687
vis.visualize(bogus_path);
8788

@@ -90,7 +91,7 @@ TEST(TrajectoryVisualizerTests, VisOptimalTrajectory)
9091

9192
// Now populated with content, should publish
9293
optimal_trajectory = xt::ones<float>({20, 2});
93-
vis.add(optimal_trajectory, "Optimal Trajectory");
94+
vis.add(optimal_trajectory, "Optimal Trajectory", bogus_stamp);
9495
vis.visualize(bogus_path);
9596

9697
rclcpp::spin_some(node->get_node_base_interface());
@@ -153,3 +154,65 @@ TEST(TrajectoryVisualizerTests, VisCandidateTrajectories)
153154
// 40 * 4, for 5 trajectory steps + 3 point steps
154155
EXPECT_EQ(recieved_msg.markers.size(), 160u);
155156
}
157+
158+
TEST(TrajectoryVisualizerTests, VisOptimalPath)
159+
{
160+
auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>("my_node");
161+
auto parameters_handler = std::make_unique<ParametersHandler>(node);
162+
builtin_interfaces::msg::Time cmd_stamp;
163+
cmd_stamp.sec = 5;
164+
cmd_stamp.nanosec = 10;
165+
166+
nav_msgs::msg::Path recieved_path;
167+
auto my_sub = node->create_subscription<nav_msgs::msg::Path>(
168+
"optimal_trajectory", 10,
169+
[&](const nav_msgs::msg::Path msg) {recieved_path = msg;});
170+
171+
// optimal_trajectory empty, should fail to publish
172+
xt::xtensor<float, 2> optimal_trajectory;
173+
TrajectoryVisualizer vis;
174+
vis.on_configure(node, "my_name", "fkmap", parameters_handler.get());
175+
vis.on_activate();
176+
vis.add(optimal_trajectory, "Optimal Trajectory", cmd_stamp);
177+
nav_msgs::msg::Path bogus_path;
178+
vis.visualize(bogus_path);
179+
180+
rclcpp::spin_some(node->get_node_base_interface());
181+
EXPECT_EQ(recieved_path.poses.size(), 0u);
182+
183+
// Now populated with content, should publish
184+
optimal_trajectory.resize({20, 2});
185+
for (unsigned int i = 0; i != optimal_trajectory.shape()[0] - 1; i++) {
186+
optimal_trajectory(i, 0) = static_cast<float>(i);
187+
optimal_trajectory(i, 1) = static_cast<float>(i);
188+
}
189+
vis.add(optimal_trajectory, "Optimal Trajectory", cmd_stamp);
190+
vis.visualize(bogus_path);
191+
192+
rclcpp::spin_some(node->get_node_base_interface());
193+
194+
// Should have a 20 points path in the map frame and with same stamp than velocity command
195+
EXPECT_EQ(recieved_path.poses.size(), 20u);
196+
EXPECT_EQ(recieved_path.header.frame_id, "fkmap");
197+
EXPECT_EQ(recieved_path.header.stamp.sec, cmd_stamp.sec);
198+
EXPECT_EQ(recieved_path.header.stamp.nanosec, cmd_stamp.nanosec);
199+
200+
tf2::Quaternion quat;
201+
for (unsigned int i = 0; i != recieved_path.poses.size() - 1; i++) {
202+
// Poses should be in map frame too
203+
EXPECT_EQ(recieved_path.poses[i].header.frame_id, "fkmap");
204+
205+
// Check positions are correct
206+
EXPECT_EQ(recieved_path.poses[i].pose.position.x, static_cast<float>(i));
207+
EXPECT_EQ(recieved_path.poses[i].pose.position.y, static_cast<float>(i));
208+
EXPECT_EQ(recieved_path.poses[i].pose.position.z, 0.06);
209+
210+
// Check orientations are correct
211+
quat.setRPY(0., 0., optimal_trajectory(i, 2));
212+
auto expected_orientation = tf2::toMsg(quat);
213+
EXPECT_EQ(recieved_path.poses[i].pose.orientation.x, expected_orientation.x);
214+
EXPECT_EQ(recieved_path.poses[i].pose.orientation.y, expected_orientation.y);
215+
EXPECT_EQ(recieved_path.poses[i].pose.orientation.z, expected_orientation.z);
216+
EXPECT_EQ(recieved_path.poses[i].pose.orientation.w, expected_orientation.w);
217+
}
218+
}

0 commit comments

Comments
 (0)