Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
trajectory_visualizer.hpp
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 #ifndef NAV2_MPPI_CONTROLLER__TOOLS__TRAJECTORY_VISUALIZER_HPP_
16 #define NAV2_MPPI_CONTROLLER__TOOLS__TRAJECTORY_VISUALIZER_HPP_
17 
18 #include <memory>
19 #include <string>
20 #include <xtensor/xtensor.hpp>
21 
22 #include "nav_msgs/msg/path.hpp"
23 #include "rclcpp/rclcpp.hpp"
24 #include "rclcpp_lifecycle/lifecycle_node.hpp"
25 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
26 
27 #include "nav2_mppi_controller/tools/parameters_handler.hpp"
28 #include "nav2_mppi_controller/tools/utils.hpp"
29 #include "nav2_mppi_controller/models/trajectories.hpp"
30 
31 namespace mppi
32 {
33 
39 {
40 public:
44  TrajectoryVisualizer() = default;
45 
53  void on_configure(
54  rclcpp_lifecycle::LifecycleNode::WeakPtr parent, const std::string & name,
55  const std::string & frame_id, ParametersHandler * parameters_handler);
56 
60  void on_cleanup();
61 
65  void on_activate();
66 
70  void on_deactivate();
71 
76  void add(const xt::xtensor<float, 2> & trajectory, const std::string & marker_namespace);
77 
82  void add(const models::Trajectories & trajectories, const std::string & marker_namespace);
83 
88  void visualize(const nav_msgs::msg::Path & plan);
89 
93  void reset();
94 
95 protected:
96  std::string frame_id_;
97  std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>>
98  trajectories_publisher_;
99  std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> transformed_path_pub_;
100 
101  std::unique_ptr<visualization_msgs::msg::MarkerArray> points_;
102  int marker_id_ = 0;
103 
104  ParametersHandler * parameters_handler_;
105 
106  size_t trajectory_step_{0};
107  size_t time_step_{0};
108 
109  rclcpp::Logger logger_{rclcpp::get_logger("MPPIController")};
110 };
111 
112 } // namespace mppi
113 
114 #endif // NAV2_MPPI_CONTROLLER__TOOLS__TRAJECTORY_VISUALIZER_HPP_
Handles getting parameters and dynamic parmaeter changes.
Visualizes trajectories for debugging.
void visualize(const nav_msgs::msg::Path &plan)
Visualize the plan.
void on_deactivate()
Deactivate object.
TrajectoryVisualizer()=default
Constructor for mppi::TrajectoryVisualizer.
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.