16 #include "nav2_mppi_controller/tools/trajectory_visualizer.hpp"
22 rclcpp_lifecycle::LifecycleNode::WeakPtr parent,
const std::string & name,
25 auto node = parent.lock();
26 logger_ = node->get_logger();
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 optimal_path_pub_ = node->create_publisher<nav_msgs::msg::Path>(
"optimal_trajectory", 1);
32 parameters_handler_ = parameters_handler;
34 auto getParam = parameters_handler->
getParamGetter(name +
".TrajectoryVisualizer");
36 getParam(trajectory_step_,
"trajectory_step", 5);
37 getParam(time_step_,
"time_step", 3);
44 trajectories_publisher_.reset();
45 transformed_path_pub_.reset();
46 optimal_path_pub_.reset();
51 trajectories_publisher_->on_activate();
52 transformed_path_pub_->on_activate();
53 optimal_path_pub_->on_activate();
58 trajectories_publisher_->on_deactivate();
59 transformed_path_pub_->on_deactivate();
60 optimal_path_pub_->on_deactivate();
64 const xt::xtensor<float, 2> & trajectory,
65 const std::string & marker_namespace,
66 const builtin_interfaces::msg::Time & cmd_stamp)
68 auto & size = trajectory.shape()[0];
73 auto add_marker = [&](
auto i) {
74 float component =
static_cast<float>(i) /
static_cast<float>(size);
76 auto pose = utils::createPose(trajectory(i, 0), trajectory(i, 1), 0.06);
79 utils::createScale(0.03, 0.03, 0.07) :
80 utils::createScale(0.07, 0.07, 0.09);
81 auto color = utils::createColor(0, component, component, 1);
82 auto marker = utils::createMarker(
83 marker_id_++, pose, scale, color, frame_id_, marker_namespace);
84 points_->markers.push_back(marker);
87 geometry_msgs::msg::PoseStamped pose_stamped;
88 pose_stamped.header.frame_id = frame_id_;
89 pose_stamped.pose = pose;
91 tf2::Quaternion quaternion_tf2;
92 quaternion_tf2.setRPY(0., 0., trajectory(i, 2));
93 pose_stamped.pose.orientation = tf2::toMsg(quaternion_tf2);
95 optimal_path_->poses.push_back(pose_stamped);
98 optimal_path_->header.stamp = cmd_stamp;
99 optimal_path_->header.frame_id = frame_id_;
100 for (
size_t i = 0; i < size; i++) {
108 auto & shape = trajectories.x.shape();
109 const float shape_1 =
static_cast<float>(shape[1]);
110 points_->markers.reserve(floor(shape[0] / trajectory_step_) * floor(shape[1] * time_step_));
112 for (
size_t i = 0; i < shape[0]; i += trajectory_step_) {
113 for (
size_t j = 0; j < shape[1]; j += time_step_) {
114 const float j_flt =
static_cast<float>(j);
115 float blue_component = 1.0f - j_flt / shape_1;
116 float green_component = j_flt / shape_1;
118 auto pose = utils::createPose(trajectories.x(i, j), trajectories.y(i, j), 0.03);
119 auto scale = utils::createScale(0.03, 0.03, 0.03);
120 auto color = utils::createColor(0, green_component, blue_component, 1);
121 auto marker = utils::createMarker(
122 marker_id_++, pose, scale, color, frame_id_, marker_namespace);
124 points_->markers.push_back(marker);
132 points_ = std::make_unique<visualization_msgs::msg::MarkerArray>();
133 optimal_path_ = std::make_unique<nav_msgs::msg::Path>();
138 if (trajectories_publisher_->get_subscription_count() > 0) {
139 trajectories_publisher_->publish(std::move(points_));
142 if (optimal_path_pub_->get_subscription_count() > 0) {
143 optimal_path_pub_->publish(std::move(optimal_path_));
148 if (transformed_path_pub_->get_subscription_count() > 0) {
149 auto plan_ptr = std::make_unique<nav_msgs::msg::Path>(plan);
150 transformed_path_pub_->publish(std::move(plan_ptr));
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 reset()
Reset object.
void on_activate()
Activate object.
void add(const xt::xtensor< float, 2 > &trajectory, const std::string &marker_namespace, const builtin_interfaces::msg::Time &cmd_stamp)
Add an optimal trajectory to visualize.
void on_cleanup()
Cleanup object on shutdown.