Go to the documentation of this file.
27 #include "etsi_its_cam_msgs/msg/cam.hpp"
31 #include "rviz_common/ros_topic_display.hpp"
32 #include "rviz_rendering/objects/movable_text.hpp"
33 #include "rviz_rendering/objects/shape.hpp"
35 #include <rclcpp/rclcpp.hpp>
61 rviz_common::RosTopicDisplay<etsi_its_cam_msgs::msg::CAM>
71 void reset()
override;
74 void processMessage(etsi_its_cam_msgs::msg::CAM::ConstSharedPtr msg)
override;
75 void update(
float wall_dt,
float ros_dt)
override;
86 std::unordered_map<int, CAMRenderObject>
cams_;
87 std::vector<std::shared_ptr<rviz_rendering::Shape>>
bboxs_;
88 std::vector<std::shared_ptr<rviz_rendering::MovableText>>
texts_;
rviz_common::properties::BoolProperty * show_meta_
std::vector< std::shared_ptr< rviz_rendering::Shape > > bboxs_
std::unordered_map< int, CAMRenderObject > cams_
void onInitialize() override
void update(float wall_dt, float ros_dt) override
rviz_common::properties::FloatProperty * buffer_timeout_
Displays an etsi_its_cam_msgs::CAM.
Ogre::ManualObject * manual_object_
std::vector< std::shared_ptr< rviz_rendering::MovableText > > texts_
rviz_common::properties::BoolProperty * show_station_id_
rclcpp::Node::SharedPtr rviz_node_
rviz_common::properties::FloatProperty * bb_scale_
rviz_common::properties::ColorProperty * text_color_property_
rviz_common::properties::BoolProperty * show_speed_
rviz_common::properties::ColorProperty * color_property_
rviz_common::properties::FloatProperty * char_height_
void processMessage(etsi_its_cam_msgs::msg::CAM::ConstSharedPtr msg) override
etsi_its_rviz_plugins
Author(s): Jean-Pierre Busch
, Guido Küppers , Lennart Reiher
autogenerated on Sun May 18 2025 02:29:25