Skip to content

Commit 676a083

Browse files
move path population in add_marker
Signed-off-by: Alyssa Agnissan <[email protected]>
1 parent a98d3f1 commit 676a083

File tree

3 files changed

+14
-40
lines changed

3 files changed

+14
-40
lines changed

nav2_mppi_controller/include/nav2_mppi_controller/tools/trajectory_visualizer.hpp

Lines changed: 0 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -89,14 +89,6 @@ class TrajectoryVisualizer
8989
*/
9090
void add(const models::Trajectories & trajectories, const std::string & marker_namespace);
9191

92-
/**
93-
* @brief Publish the optimal trajectory in the form of a path message
94-
* @param trajectory Optimal trajectory
95-
*/
96-
void populate_optimal_path(
97-
const xt::xtensor<float, 2> & optimal_traj,
98-
const builtin_interfaces::msg::Time & cmd_stamp);
99-
10092
/**
10193
* @brief Visualize the plan
10294
* @param plan Plan to visualize

nav2_mppi_controller/src/trajectory_visualizer.cpp

Lines changed: 13 additions & 31 deletions
Original file line numberDiff line numberDiff line change
@@ -82,13 +82,24 @@ void TrajectoryVisualizer::add(
8282
auto marker = utils::createMarker(
8383
marker_id_++, pose, scale, color, frame_id_, marker_namespace);
8484
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);
8596
};
8697

98+
optimal_path_->header.stamp = cmd_stamp;
99+
optimal_path_->header.frame_id = frame_id_;
87100
for (size_t i = 0; i < size; i++) {
88101
add_marker(i);
89102
}
90-
91-
populate_optimal_path(trajectory, cmd_stamp);
92103
}
93104

94105
void TrajectoryVisualizer::add(
@@ -140,33 +151,4 @@ void TrajectoryVisualizer::visualize(const nav_msgs::msg::Path & plan)
140151
}
141152
}
142153

143-
void TrajectoryVisualizer::populate_optimal_path(
144-
const xt::xtensor<float, 2> & optimal_traj,
145-
const builtin_interfaces::msg::Time & cmd_stamp)
146-
{
147-
auto & size = optimal_traj.shape()[0];
148-
if (size == 0) {
149-
return;
150-
}
151-
152-
optimal_path_->header.stamp = cmd_stamp;
153-
optimal_path_->header.frame_id = frame_id_;
154-
155-
for (size_t i = 0; i < size; i++) {
156-
// create new pose for the path
157-
geometry_msgs::msg::PoseStamped pose_stamped;
158-
pose_stamped.header.frame_id = frame_id_;
159-
160-
// position & orientation
161-
pose_stamped.pose = utils::createPose(optimal_traj(i, 0), optimal_traj(i, 1), 0.0);
162-
163-
tf2::Quaternion quaternion_tf2;
164-
quaternion_tf2.setRPY(0., 0., optimal_traj(i, 2));
165-
pose_stamped.pose.orientation = tf2::toMsg(quaternion_tf2);
166-
167-
// add pose to the path
168-
optimal_path_->poses.push_back(pose_stamped);
169-
}
170-
}
171-
172154
} // namespace mppi

nav2_mppi_controller/test/trajectory_visualizer_tests.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -205,7 +205,7 @@ TEST(TrajectoryVisualizerTests, VisOptimalPath)
205205
// Check positions are correct
206206
EXPECT_EQ(recieved_path.poses[i].pose.position.x, static_cast<float>(i));
207207
EXPECT_EQ(recieved_path.poses[i].pose.position.y, static_cast<float>(i));
208-
EXPECT_EQ(recieved_path.poses[i].pose.position.z, 0.0);
208+
EXPECT_EQ(recieved_path.poses[i].pose.position.z, 0.06);
209209

210210
// Check orientations are correct
211211
quat.setRPY(0., 0., optimal_trajectory(i, 2));

0 commit comments

Comments
 (0)