15 #ifndef NAV2_MPPI_CONTROLLER__TOOLS__TRAJECTORY_VISUALIZER_HPP_
16 #define NAV2_MPPI_CONTROLLER__TOOLS__TRAJECTORY_VISUALIZER_HPP_
22 #pragma GCC diagnostic push
23 #pragma GCC diagnostic ignored "-Warray-bounds"
24 #pragma GCC diagnostic ignored "-Wstringop-overflow"
25 #include <xtensor/xtensor.hpp>
26 #pragma GCC diagnostic pop
28 #include "nav_msgs/msg/path.hpp"
29 #include "rclcpp/rclcpp.hpp"
30 #include "rclcpp_lifecycle/lifecycle_node.hpp"
31 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
33 #include "nav2_mppi_controller/tools/parameters_handler.hpp"
34 #include "nav2_mppi_controller/tools/utils.hpp"
35 #include "nav2_mppi_controller/models/trajectories.hpp"
60 rclcpp_lifecycle::LifecycleNode::WeakPtr parent,
const std::string & name,
83 const xt::xtensor<float, 2> & trajectory,
const std::string & marker_namespace,
84 const builtin_interfaces::msg::Time & cmd_stamp);
96 void visualize(
const nav_msgs::msg::Path & plan);
104 std::string frame_id_;
105 std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>>
106 trajectories_publisher_;
107 std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> transformed_path_pub_;
108 std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> optimal_path_pub_;
110 std::unique_ptr<nav_msgs::msg::Path> optimal_path_;
111 std::unique_ptr<visualization_msgs::msg::MarkerArray> points_;
116 size_t trajectory_step_{0};
117 size_t time_step_{0};
119 rclcpp::Logger logger_{rclcpp::get_logger(
"MPPIController")};
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 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.