Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
trajectory_visualizer.cpp
1 // Copyright (c) 2022 Samsung Research America, @artofnothingness Alexey Budyakov
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include <memory>
16 #include "nav2_mppi_controller/tools/trajectory_visualizer.hpp"
17 
18 namespace mppi
19 {
20 
22  rclcpp_lifecycle::LifecycleNode::WeakPtr parent, const std::string & name,
23  const std::string & frame_id, ParametersHandler * parameters_handler)
24 {
25  auto node = parent.lock();
26  logger_ = node->get_logger();
27  frame_id_ = frame_id;
28  trajectories_publisher_ =
29  node->create_publisher<visualization_msgs::msg::MarkerArray>("~/candidate_trajectories", 1);
30  transformed_path_pub_ = node->create_publisher<nav_msgs::msg::Path>(
31  "~/transformed_global_plan", 1);
32  optimal_path_pub_ = node->create_publisher<nav_msgs::msg::Path>("~/optimal_path", 1);
33  parameters_handler_ = parameters_handler;
34 
35  auto getParam = parameters_handler->getParamGetter(name + ".TrajectoryVisualizer");
36 
37  getParam(trajectory_step_, "trajectory_step", 5);
38  getParam(time_step_, "time_step", 3);
39 
40  reset();
41 }
42 
44 {
45  trajectories_publisher_.reset();
46  transformed_path_pub_.reset();
47  optimal_path_pub_.reset();
48 }
49 
51 {
52  trajectories_publisher_->on_activate();
53  transformed_path_pub_->on_activate();
54  optimal_path_pub_->on_activate();
55 }
56 
58 {
59  trajectories_publisher_->on_deactivate();
60  transformed_path_pub_->on_deactivate();
61  optimal_path_pub_->on_deactivate();
62 }
63 
65  const Eigen::ArrayXXf & trajectory,
66  const std::string & marker_namespace,
67  const builtin_interfaces::msg::Time & cmd_stamp)
68 {
69  size_t size = trajectory.rows();
70  if (!size) {
71  return;
72  }
73 
74  auto add_marker = [&](auto i) {
75  float component = static_cast<float>(i) / static_cast<float>(size);
76 
77  auto pose = utils::createPose(trajectory(i, 0), trajectory(i, 1), 0.06);
78  auto scale =
79  i != size - 1 ?
80  utils::createScale(0.03, 0.03, 0.07) :
81  utils::createScale(0.07, 0.07, 0.09);
82  auto color = utils::createColor(0, component, component, 1);
83  auto marker = utils::createMarker(
84  marker_id_++, pose, scale, color, frame_id_, marker_namespace);
85  points_->markers.push_back(marker);
86 
87  // populate optimal path
88  geometry_msgs::msg::PoseStamped pose_stamped;
89  pose_stamped.header.frame_id = frame_id_;
90  pose_stamped.pose = pose;
91 
92  tf2::Quaternion quaternion_tf2;
93  quaternion_tf2.setRPY(0., 0., trajectory(i, 2));
94  pose_stamped.pose.orientation = tf2::toMsg(quaternion_tf2);
95 
96  optimal_path_->poses.push_back(pose_stamped);
97  };
98 
99  optimal_path_->header.stamp = cmd_stamp;
100  optimal_path_->header.frame_id = frame_id_;
101  for (size_t i = 0; i < size; i++) {
102  add_marker(i);
103  }
104 }
105 
107  const models::Trajectories & trajectories, const std::string & marker_namespace)
108 {
109  size_t n_rows = trajectories.x.rows();
110  size_t n_cols = trajectories.x.cols();
111  const float shape_1 = static_cast<float>(n_cols);
112  points_->markers.reserve(floor(n_rows / trajectory_step_) * floor(n_cols * time_step_));
113 
114  for (size_t i = 0; i < n_rows; i += trajectory_step_) {
115  for (size_t j = 0; j < n_cols; j += time_step_) {
116  const float j_flt = static_cast<float>(j);
117  float blue_component = 1.0f - j_flt / shape_1;
118  float green_component = j_flt / shape_1;
119 
120  auto pose = utils::createPose(trajectories.x(i, j), trajectories.y(i, j), 0.03);
121  auto scale = utils::createScale(0.03, 0.03, 0.03);
122  auto color = utils::createColor(0, green_component, blue_component, 1);
123  auto marker = utils::createMarker(
124  marker_id_++, pose, scale, color, frame_id_, marker_namespace);
125 
126  points_->markers.push_back(marker);
127  }
128  }
129 }
130 
132 {
133  marker_id_ = 0;
134  points_ = std::make_unique<visualization_msgs::msg::MarkerArray>();
135  optimal_path_ = std::make_unique<nav_msgs::msg::Path>();
136 }
137 
138 void TrajectoryVisualizer::visualize(const nav_msgs::msg::Path & plan)
139 {
140  if (trajectories_publisher_->get_subscription_count() > 0) {
141  trajectories_publisher_->publish(std::move(points_));
142  }
143 
144  if (optimal_path_pub_->get_subscription_count() > 0) {
145  optimal_path_pub_->publish(std::move(optimal_path_));
146  }
147 
148  reset();
149 
150  if (transformed_path_pub_->get_subscription_count() > 0) {
151  auto plan_ptr = std::make_unique<nav_msgs::msg::Path>(plan);
152  transformed_path_pub_->publish(std::move(plan_ptr));
153  }
154 }
155 
156 } // namespace mppi
Handles getting parameters and dynamic parameter changes.
auto getParamGetter(const std::string &ns)
Get an object to retrieve parameters.
void add(const Eigen::ArrayXXf &trajectory, const std::string &marker_namespace, const builtin_interfaces::msg::Time &cmd_stamp)
Add an optimal trajectory to visualize.
void visualize(const nav_msgs::msg::Path &plan)
Visualize the plan.
void on_deactivate()
Deactivate object.
void on_configure(rclcpp_lifecycle::LifecycleNode::WeakPtr parent, const std::string &name, const std::string &frame_id, ParametersHandler *parameters_handler)
Configure trajectory visualizer.
void on_activate()
Activate object.
void on_cleanup()
Cleanup object on shutdown.
Candidate Trajectories.