Nav2 Navigation Stack - humble  humble
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>("/trajectories", 1);
30  transformed_path_pub_ = node->create_publisher<nav_msgs::msg::Path>("transformed_global_plan", 1);
31  parameters_handler_ = parameters_handler;
32 
33  auto getParam = parameters_handler->getParamGetter(name + ".TrajectoryVisualizer");
34 
35  getParam(trajectory_step_, "trajectory_step", 5);
36  getParam(time_step_, "time_step", 3);
37 
38  reset();
39 }
40 
42 {
43  trajectories_publisher_.reset();
44  transformed_path_pub_.reset();
45 }
46 
48 {
49  trajectories_publisher_->on_activate();
50  transformed_path_pub_->on_activate();
51 }
52 
54 {
55  trajectories_publisher_->on_deactivate();
56  transformed_path_pub_->on_deactivate();
57 }
58 
60  const xt::xtensor<float, 2> & trajectory, const std::string & marker_namespace)
61 {
62  auto & size = trajectory.shape()[0];
63  if (!size) {
64  return;
65  }
66 
67  auto add_marker = [&](auto i) {
68  float component = static_cast<float>(i) / static_cast<float>(size);
69 
70  auto pose = utils::createPose(trajectory(i, 0), trajectory(i, 1), 0.06);
71  auto scale =
72  i != size - 1 ?
73  utils::createScale(0.03, 0.03, 0.07) :
74  utils::createScale(0.07, 0.07, 0.09);
75  auto color = utils::createColor(0, component, component, 1);
76  auto marker = utils::createMarker(
77  marker_id_++, pose, scale, color, frame_id_, marker_namespace);
78  points_->markers.push_back(marker);
79  };
80 
81  for (size_t i = 0; i < size; i++) {
82  add_marker(i);
83  }
84 }
85 
87  const models::Trajectories & trajectories, const std::string & marker_namespace)
88 {
89  auto & shape = trajectories.x.shape();
90  const float shape_1 = static_cast<float>(shape[1]);
91  points_->markers.reserve(floor(shape[0] / trajectory_step_) * floor(shape[1] * time_step_));
92 
93  for (size_t i = 0; i < shape[0]; i += trajectory_step_) {
94  for (size_t j = 0; j < shape[1]; j += time_step_) {
95  const float j_flt = static_cast<float>(j);
96  float blue_component = 1.0f - j_flt / shape_1;
97  float green_component = j_flt / shape_1;
98 
99  auto pose = utils::createPose(trajectories.x(i, j), trajectories.y(i, j), 0.03);
100  auto scale = utils::createScale(0.03, 0.03, 0.03);
101  auto color = utils::createColor(0, green_component, blue_component, 1);
102  auto marker = utils::createMarker(
103  marker_id_++, pose, scale, color, frame_id_, marker_namespace);
104 
105  points_->markers.push_back(marker);
106  }
107  }
108 }
109 
111 {
112  marker_id_ = 0;
113  points_ = std::make_unique<visualization_msgs::msg::MarkerArray>();
114 }
115 
116 void TrajectoryVisualizer::visualize(const nav_msgs::msg::Path & plan)
117 {
118  if (trajectories_publisher_->get_subscription_count() > 0) {
119  trajectories_publisher_->publish(std::move(points_));
120  }
121 
122  reset();
123 
124  if (transformed_path_pub_->get_subscription_count() > 0) {
125  auto plan_ptr = std::make_unique<nav_msgs::msg::Path>(plan);
126  transformed_path_pub_->publish(std::move(plan_ptr));
127  }
128 }
129 
130 } // namespace mppi
Handles getting parameters and dynamic parmaeter changes.
auto getParamGetter(const std::string &ns)
Get an object to retreive parameters.
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 add(const xt::xtensor< float, 2 > &trajectory, const std::string &marker_namespace)
Add an optimal trajectory to visualize.
void on_activate()
Activate object.
void on_cleanup()
Cleanup object on shutdown.
Candidate Trajectories.