mapem_display.hpp
Go to the documentation of this file.
1 
25 #pragma once
26 
27 #include "etsi_its_mapem_ts_msgs/msg/mapem.hpp"
28 #include "etsi_its_spatem_ts_msgs/msg/spatem.hpp"
29 
31 
32 #include "rviz_common/ros_topic_display.hpp"
33 #include "rviz_rendering/objects/billboard_line.hpp"
34 #include "rviz_rendering/objects/movable_text.hpp"
35 #include "rviz_rendering/objects/shape.hpp"
36 
37 #include <rclcpp/rclcpp.hpp>
38 
39 namespace Ogre
40 {
41 class ManualObject;
42 }
43 
44 namespace rviz_common
45 {
46 namespace properties
47 {
48  class ColorProperty;
49  class FloatProperty;
50  class RosTopicProperty;
51  class QosProfileProperty;
52 } // namespace properties
53 } // namespace rviz_common
54 
55 namespace etsi_its_msgs
56 {
57 namespace displays
58 {
59 
64 class MAPEMDisplay : public
65  rviz_common::RosTopicDisplay<etsi_its_mapem_ts_msgs::msg::MAPEM>
66 {
67  Q_OBJECT
68 
69 public:
70  MAPEMDisplay();
71  ~MAPEMDisplay() override;
72 
73  void onInitialize() override;
74 
75  void reset() override;
76 
77 protected Q_SLOTS:
78  void changedSPATEMViz();
79  void changedSPATEMTopic();
80  void changedMAPEMViz();
81 
82 protected:
83  void processMessage(etsi_its_mapem_ts_msgs::msg::MAPEM::ConstSharedPtr msg) override;
84  void update(float wall_dt, float ros_dt) override;
85  void SPATEMCallback(etsi_its_spatem_ts_msgs::msg::SPATEM::ConstSharedPtr msg);
86 
87  void RenderMapemShapes(Ogre::SceneNode *child_scene_node);
88  void RenderMapemShapesLane(Ogre::SceneNode *child_scene_node, IntersectionLane& lane);
89  void RenderMapemTexts(Ogre::SceneNode *child_scene_node, IntersectionRenderObject& intsctn);
90  void RenderSpatemShapes(Ogre::SceneNode *child_scene_node, IntersectionLane& lane, IntersectionMovementState* intersection_movement_state);
91  void RenderSpatemTexts(Ogre::SceneNode *child_scene_node, IntersectionLane& lane, IntersectionMovementState* intersection_movement_state);
92 
93  Ogre::ManualObject *manual_object_;
94 
95  rclcpp::Node::SharedPtr rviz_node_;
96  rclcpp::Subscription<etsi_its_spatem_ts_msgs::msg::SPATEM>::SharedPtr spatem_subscriber_;
97  rclcpp::QoS spatem_qos_profile_ = rclcpp::QoS(1);
98 
99  // Properties
100  rviz_common::properties::BoolProperty *show_meta_spatem_, *show_meta_mapem_, *viz_spatem_, *viz_mapem_;
104  rviz_common::properties::RosTopicProperty *spatem_topic_property_;
105  rviz_common::properties::QosProfileProperty *spatem_qos_property_;
106 
107  // Each Utm-SceneNode represents an utm frame
108  std::map<std::string, Ogre::SceneNode*> scene_nodes_utm_;
109 
110  // Each Junction-SceneNode represents the origin of a junction coordinate frame
111  std::map<uint, Ogre::SceneNode*> scene_nodes_junctions_;
112 
113  std::unordered_map<int, IntersectionRenderObject> intersections_;
114  std::vector<std::shared_ptr<rviz_rendering::Shape>> intsct_ref_points_, signal_groups_;
115  std::vector<std::shared_ptr<rviz_rendering::BillboardLine>> lane_lines_;
116  std::vector<std::shared_ptr<rviz_rendering::MovableText>> texts_;
117 
118  uint64_t received_spats_=0;
119 };
120 
121 } // namespace displays
122 } // namespace etsi_its_msgs
etsi_its_msgs::displays::MAPEMDisplay::spatem_qos_property_
rviz_common::properties::QosProfileProperty * spatem_qos_property_
Definition: mapem_display.hpp:105
etsi_its_msgs::displays::MAPEMDisplay::char_height_mapem_
rviz_common::properties::FloatProperty * char_height_mapem_
Definition: mapem_display.hpp:102
etsi_its_msgs::displays::MAPEMDisplay::spatem_qos_profile_
rclcpp::QoS spatem_qos_profile_
Definition: mapem_display.hpp:97
etsi_its_msgs::displays::MAPEMDisplay::rviz_node_
rclcpp::Node::SharedPtr rviz_node_
Definition: mapem_display.hpp:95
etsi_its_msgs::displays::MAPEMDisplay::show_spatem_max_end_time
rviz_common::properties::BoolProperty * show_spatem_max_end_time
Definition: mapem_display.hpp:101
etsi_its_msgs::displays::MAPEMDisplay::color_property_ingress_
rviz_common::properties::ColorProperty * color_property_ingress_
Definition: mapem_display.hpp:103
etsi_its_msgs::displays::MAPEMDisplay::mapem_sphere_scale_property_
rviz_common::properties::FloatProperty * mapem_sphere_scale_property_
Definition: mapem_display.hpp:102
Ogre
Definition: cam_display.hpp:37
etsi_its_msgs::displays::MAPEMDisplay::viz_mapem_
rviz_common::properties::BoolProperty * viz_mapem_
Definition: mapem_display.hpp:100
etsi_its_msgs::displays::MAPEMDisplay::spatem_sphere_scale_property_
rviz_common::properties::FloatProperty * spatem_sphere_scale_property_
Definition: mapem_display.hpp:102
etsi_its_msgs::displays::MAPEMDisplay::received_spats_
uint64_t received_spats_
Definition: mapem_display.hpp:118
intersection_render_object.hpp
etsi_its_msgs::displays::IntersectionRenderObject
Definition: intersection_render_object.hpp:64
etsi_its_msgs::displays::MAPEMDisplay::color_property_egress_
rviz_common::properties::ColorProperty * color_property_egress_
Definition: mapem_display.hpp:103
etsi_its_msgs::displays::MAPEMDisplay::RenderMapemShapesLane
void RenderMapemShapesLane(Ogre::SceneNode *child_scene_node, IntersectionLane &lane)
Definition: mapem_display.cpp:306
etsi_its_msgs::displays::MAPEMDisplay::text_color_property_mapem_
rviz_common::properties::ColorProperty * text_color_property_mapem_
Definition: mapem_display.hpp:103
etsi_its_msgs::displays::MAPEMDisplay::intsct_ref_points_
std::vector< std::shared_ptr< rviz_rendering::Shape > > intsct_ref_points_
Definition: mapem_display.hpp:114
etsi_its_msgs::displays::MAPEMDisplay::MAPEMDisplay
MAPEMDisplay()
Definition: mapem_display.cpp:56
etsi_its_msgs::displays::MAPEMDisplay::~MAPEMDisplay
~MAPEMDisplay() override
Definition: mapem_display.cpp:135
etsi_its_msgs::displays::MAPEMDisplay::manual_object_
Ogre::ManualObject * manual_object_
Definition: mapem_display.hpp:93
etsi_its_msgs::displays::MAPEMDisplay::show_spatem_likely_time
rviz_common::properties::BoolProperty * show_spatem_likely_time
Definition: mapem_display.hpp:101
etsi_its_msgs::displays::MAPEMDisplay
Displays an etsi_its_mapem_ts_msgs::MAPEM.
Definition: mapem_display.hpp:64
etsi_its_msgs::displays::MAPEMDisplay::texts_
std::vector< std::shared_ptr< rviz_rendering::MovableText > > texts_
Definition: mapem_display.hpp:116
etsi_its_msgs::displays::MAPEMDisplay::SPATEMCallback
void SPATEMCallback(etsi_its_spatem_ts_msgs::msg::SPATEM::ConstSharedPtr msg)
Definition: mapem_display.cpp:210
etsi_its_msgs::displays::MAPEMDisplay::update
void update(float wall_dt, float ros_dt) override
Definition: mapem_display.cpp:446
etsi_its_msgs::displays::MAPEMDisplay::spatem_topic_property_
rviz_common::properties::RosTopicProperty * spatem_topic_property_
Definition: mapem_display.hpp:104
etsi_its_msgs::displays::MAPEMDisplay::scene_nodes_junctions_
std::map< uint, Ogre::SceneNode * > scene_nodes_junctions_
Definition: mapem_display.hpp:111
etsi_its_msgs::displays::MAPEMDisplay::spatem_timeout_
rviz_common::properties::FloatProperty * spatem_timeout_
Definition: mapem_display.hpp:102
etsi_its_msgs::displays::MAPEMDisplay::mapem_timeout_
rviz_common::properties::FloatProperty * mapem_timeout_
Definition: mapem_display.hpp:102
etsi_its_msgs::displays::MAPEMDisplay::signal_groups_
std::vector< std::shared_ptr< rviz_rendering::Shape > > signal_groups_
Definition: mapem_display.hpp:114
etsi_its_msgs::displays::MAPEMDisplay::show_spatem_min_end_time
rviz_common::properties::BoolProperty * show_spatem_min_end_time
Definition: mapem_display.hpp:101
etsi_its_msgs::displays::MAPEMDisplay::RenderMapemShapes
void RenderMapemShapes(Ogre::SceneNode *child_scene_node)
Definition: mapem_display.cpp:289
etsi_its_msgs::displays::MAPEMDisplay::lane_lines_
std::vector< std::shared_ptr< rviz_rendering::BillboardLine > > lane_lines_
Definition: mapem_display.hpp:115
etsi_its_msgs::displays::MAPEMDisplay::processMessage
void processMessage(etsi_its_mapem_ts_msgs::msg::MAPEM::ConstSharedPtr msg) override
Definition: mapem_display.cpp:260
etsi_its_msgs::displays::MAPEMDisplay::onInitialize
void onInitialize() override
Definition: mapem_display.cpp:138
rviz_common
Definition: cam_display.hpp:42
etsi_its_msgs::displays::MAPEMDisplay::changedSPATEMViz
void changedSPATEMViz()
Definition: mapem_display.cpp:161
etsi_its_msgs::displays::MAPEMDisplay::show_spatem_start_time
rviz_common::properties::BoolProperty * show_spatem_start_time
Definition: mapem_display.hpp:101
etsi_its_msgs::displays::MAPEMDisplay::scene_nodes_utm_
std::map< std::string, Ogre::SceneNode * > scene_nodes_utm_
Definition: mapem_display.hpp:108
etsi_its_msgs::displays::MAPEMDisplay::lane_width_property_
rviz_common::properties::FloatProperty * lane_width_property_
Definition: mapem_display.hpp:102
etsi_its_msgs::displays::MAPEMDisplay::RenderSpatemTexts
void RenderSpatemTexts(Ogre::SceneNode *child_scene_node, IntersectionLane &lane, IntersectionMovementState *intersection_movement_state)
Definition: mapem_display.cpp:375
etsi_its_msgs::displays::MAPEMDisplay::show_meta_spatem_
rviz_common::properties::BoolProperty * show_meta_spatem_
Definition: mapem_display.hpp:100
etsi_its_msgs::displays::MAPEMDisplay::show_spatem_next_time
rviz_common::properties::BoolProperty * show_spatem_next_time
Definition: mapem_display.hpp:101
etsi_its_msgs::displays::MAPEMDisplay::show_spatem_confidence
rviz_common::properties::BoolProperty * show_spatem_confidence
Definition: mapem_display.hpp:101
etsi_its_msgs::displays::IntersectionMovementState
Definition: intersection_render_object.hpp:52
etsi_its_msgs::displays::MAPEMDisplay::RenderSpatemShapes
void RenderSpatemShapes(Ogre::SceneNode *child_scene_node, IntersectionLane &lane, IntersectionMovementState *intersection_movement_state)
Definition: mapem_display.cpp:341
etsi_its_msgs::displays::MAPEMDisplay::viz_spatem_
rviz_common::properties::BoolProperty * viz_spatem_
Definition: mapem_display.hpp:100
etsi_its_msgs::displays::MAPEMDisplay::char_height_spatem_
rviz_common::properties::FloatProperty * char_height_spatem_
Definition: mapem_display.hpp:102
etsi_its_msgs::displays::MAPEMDisplay::intersections_
std::unordered_map< int, IntersectionRenderObject > intersections_
Definition: mapem_display.hpp:113
etsi_its_msgs::displays::MAPEMDisplay::changedMAPEMViz
void changedMAPEMViz()
etsi_its_msgs::displays::MAPEMDisplay::changedSPATEMTopic
void changedSPATEMTopic()
Definition: mapem_display.cpp:169
etsi_its_msgs::displays::MAPEMDisplay::RenderMapemTexts
void RenderMapemTexts(Ogre::SceneNode *child_scene_node, IntersectionRenderObject &intsctn)
Definition: mapem_display.cpp:326
etsi_its_msgs
Definition: cam_display.hpp:51
etsi_its_msgs::displays::MAPEMDisplay::show_meta_mapem_
rviz_common::properties::BoolProperty * show_meta_mapem_
Definition: mapem_display.hpp:100
etsi_its_msgs::displays::MAPEMDisplay::reset
void reset() override
Definition: mapem_display.cpp:152
etsi_its_msgs::displays::IntersectionLane
Definition: intersection_render_object.hpp:44
etsi_its_msgs::displays::MAPEMDisplay::spatem_subscriber_
rclcpp::Subscription< etsi_its_spatem_ts_msgs::msg::SPATEM >::SharedPtr spatem_subscriber_
Definition: mapem_display.hpp:96
etsi_its_msgs::displays::MAPEMDisplay::text_color_property_spatem_
rviz_common::properties::ColorProperty * text_color_property_spatem_
Definition: mapem_display.hpp:103


etsi_its_rviz_plugins
Author(s): Jean-Pierre Busch , Guido Küppers , Lennart Reiher
autogenerated on Sun May 18 2025 02:29:25