19#include <rclcpp/rclcpp.hpp>
20#include <carma_planning_msgs/msg/trajectory_plan.hpp>
21#include <carma_ros2_utils/carma_lifecycle_node.hpp>
22#include <visualization_msgs/msg/marker_array.hpp>
40 carma_ros2_utils::SubPtr<carma_planning_msgs::msg::TrajectoryPlan>
traj_sub_;
TrajectoryVisualizer(const rclcpp::NodeOptions &)
TrajectoryVisualizer constructor.
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &)
void callbackPlanTrajectory(carma_planning_msgs::msg::TrajectoryPlan::UniquePtr msg)
carma_ros2_utils::PubPtr< visualization_msgs::msg::MarkerArray > traj_marker_pub_
size_t prev_marker_list_size_
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::TrajectoryPlan > traj_sub_
max_speed values for trajectory_visualizer