|
Nav2 Navigation Stack - humble
humble
ROS 2 Navigation Stack
|
Visualizes trajectories for debugging. More...
#include <nav2_mppi_controller/include/nav2_mppi_controller/tools/trajectory_visualizer.hpp>

Public Member Functions | |
| 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. More... | |
| void | on_cleanup () |
| Cleanup object on shutdown. | |
| void | on_activate () |
| Activate object. | |
| void | on_deactivate () |
| Deactivate object. | |
| void | add (const xt::xtensor< float, 2 > &trajectory, const std::string &marker_namespace) |
| Add an optimal trajectory to visualize. More... | |
| void | add (const models::Trajectories &trajectories, const std::string &marker_namespace) |
| Add candidate trajectories to visualize. More... | |
| void | visualize (const nav_msgs::msg::Path &plan) |
| Visualize the plan. More... | |
| void | reset () |
| Reset object. | |
Protected Attributes | |
| std::string | frame_id_ |
| std::shared_ptr< rclcpp_lifecycle::LifecyclePublisher< visualization_msgs::msg::MarkerArray > > | trajectories_publisher_ |
| std::shared_ptr< rclcpp_lifecycle::LifecyclePublisher< nav_msgs::msg::Path > > | transformed_path_pub_ |
| std::unique_ptr< visualization_msgs::msg::MarkerArray > | points_ |
| int | marker_id_ = 0 |
| ParametersHandler * | parameters_handler_ |
| size_t | trajectory_step_ {0} |
| size_t | time_step_ {0} |
| rclcpp::Logger | logger_ {rclcpp::get_logger("MPPIController")} |
Visualizes trajectories for debugging.
Definition at line 38 of file trajectory_visualizer.hpp.
| void mppi::TrajectoryVisualizer::add | ( | const models::Trajectories & | trajectories, |
| const std::string & | marker_namespace | ||
| ) |
Add candidate trajectories to visualize.
| trajectories | Candidate trajectories |
Definition at line 86 of file trajectory_visualizer.cpp.
| void mppi::TrajectoryVisualizer::add | ( | const xt::xtensor< float, 2 > & | trajectory, |
| const std::string & | marker_namespace | ||
| ) |
Add an optimal trajectory to visualize.
| trajectory | Optimal trajectory |
Definition at line 59 of file trajectory_visualizer.cpp.
Referenced by nav2_mppi_controller::MPPIController::visualize().

| void mppi::TrajectoryVisualizer::on_configure | ( | rclcpp_lifecycle::LifecycleNode::WeakPtr | parent, |
| const std::string & | name, | ||
| const std::string & | frame_id, | ||
| ParametersHandler * | parameters_handler | ||
| ) |
Configure trajectory visualizer.
| parent | WeakPtr to node |
| name | Name of plugin |
| frame_id | Frame to publish trajectories in |
| dynamic_parameter_handler | Parameter handler object |
Definition at line 21 of file trajectory_visualizer.cpp.
References mppi::ParametersHandler::getParamGetter(), and reset().
Referenced by nav2_mppi_controller::MPPIController::configure().


| void mppi::TrajectoryVisualizer::visualize | ( | const nav_msgs::msg::Path & | plan | ) |
Visualize the plan.
| plan | Plan to visualize |
Definition at line 116 of file trajectory_visualizer.cpp.
References reset().
Referenced by nav2_mppi_controller::MPPIController::visualize().

