19#include <rclcpp/rclcpp.hpp>
21#include <carma_perception_msgs/msg/external_object_list.hpp>
22#include <carma_perception_msgs/msg/roadway_obstacle_list.hpp>
23#include <visualization_msgs/msg/marker_array.hpp>
24#include <visualization_msgs/msg/marker.hpp>
26#include <carma_ros2_utils/carma_lifecycle_node.hpp>
28#include <tf2/LinearMath/Quaternion.h>
29#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
38 class Node :
public carma_ros2_utils::CarmaLifecycleNode
68 const std_msgs::msg::Header& header,
69 const geometry_msgs::msg::Pose& pose,
71 const std::string& ns,
72 const geometry_msgs::msg::Vector3& size);
90 explicit Node(
const rclcpp::NodeOptions &);
95 rcl_interfaces::msg::SetParametersResult
This node provides RViz visualization messages for recieved ExternalObject and RoadwayObstacle messag...
void roadway_obstacles_callback(carma_perception_msgs::msg::RoadwayObstacleList::UniquePtr msg)
Roadway obstacles callback. Converts the message to a visualization message to republish.
void createPedestrianMarker(visualization_msgs::msg::Marker &marker, const std_msgs::msg::Header &header, const geometry_msgs::msg::Pose &pose, size_t id, const std::string &ns, const geometry_msgs::msg::Vector3 &size)
Creates a pedestrian marker with specialized visualization.
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > ¶meters)
Example callback for dynamic parameter updates.
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &)
carma_ros2_utils::PubPtr< visualization_msgs::msg::MarkerArray > roadway_obstacles_viz_pub_
void clear_and_update_old_objects(visualization_msgs::msg::MarkerArray &viz_msg, size_t &old_size)
Adds a marker deletion for a number of markers which is the delta between the new marker count and th...
carma_ros2_utils::SubPtr< carma_perception_msgs::msg::ExternalObjectList > external_objects_sub_
size_t prev_roadway_obstacles_size_
size_t prev_external_objects_size_
Node(const rclcpp::NodeOptions &)
Node constructor.
carma_ros2_utils::SubPtr< carma_perception_msgs::msg::RoadwayObstacleList > roadway_obstacles_sub_
carma_ros2_utils::PubPtr< visualization_msgs::msg::MarkerArray > external_objects_viz_pub_
void external_objects_callback(carma_perception_msgs::msg::ExternalObjectList::UniquePtr msg)
External objects callback. Converts the message to a visualization message to republish.
Stuct containing the algorithm configuration values for object_visualizer.