intersection_render_object.hpp
Go to the documentation of this file.
1 
25 #include "etsi_its_mapem_ts_msgs/msg/mapem.hpp"
26 #include "etsi_its_spatem_ts_msgs/msg/spatem.hpp"
27 #include <geometry_msgs/msg/point.hpp>
28 #include <std_msgs/msg/header.hpp>
29 
30 #include <rclcpp/rclcpp.hpp>
31 
32 #include <tf2/LinearMath/Quaternion.h>
33 
34 #include "rviz_common/validate_floats.hpp"
35 
36 namespace etsi_its_msgs
37 {
38 namespace displays
39 {
40 
43 
44 typedef struct IntersectionLane {
45  uint8_t lane_id;
48  std::vector<geometry_msgs::msg::Point> nodes; // relative to ref_point of intersection
49  std::vector<uint8_t> signal_group_ids;
51 
52 typedef struct IntersectionMovementState {
53  std_msgs::msg::Header header;
54  uint8_t signal_group_id;
55  etsi_its_spatem_ts_msgs::msg::MovementPhaseState phase_state;
56  etsi_its_spatem_ts_msgs::msg::TimeChangeDetails::SharedPtr time_change_details;
57 
59 
65 {
66  public:
67  IntersectionRenderObject(etsi_its_mapem_ts_msgs::msg::IntersectionGeometry intersection, bool timestamp_is_present, etsi_its_mapem_ts_msgs::msg::MinuteOfTheYear mapem_stamp, rclcpp::Time receive_time);
68 
73  bool validateFloats();
74 
81  double getAge(rclcpp::Time now);
82 
89  void removeOutdatedMovemenStates(rclcpp::Time now, double timeout);
90 
96  unsigned int getIntersectionID();
97 
103  std_msgs::msg::Header getHeader();
104 
110  geometry_msgs::msg::Point getRefPosition();
111 
117  tf2::Quaternion getGridConvergenceQuaternion();
118 
119  // public member variables
120  std::vector<IntersectionLane> lanes;
121  std::unordered_map<int, IntersectionMovementState> movement_states;
122 
123  private:
124  // member variables
125  std_msgs::msg::Header header;
126  unsigned int intersection_id;
127  std::vector<unsigned int> layer_ids;
128  geometry_msgs::msg::PointStamped ref_point;
130 };
131 
132 } // namespace displays
133 } // namespace etsi_its_msgs
etsi_its_msgs::displays::parking
@ parking
Definition: intersection_render_object.hpp:42
etsi_its_msgs::displays::crosswalk
@ crosswalk
Definition: intersection_render_object.hpp:42
etsi_its_msgs::displays::bidirectional
@ bidirectional
Definition: intersection_render_object.hpp:41
etsi_its_msgs::displays::IntersectionRenderObject::getIntersectionID
unsigned int getIntersectionID()
Get the IntersectionID.
Definition: intersection_render_object.cpp:146
etsi_its_msgs::displays::IntersectionRenderObject::validateFloats
bool validateFloats()
This function validates all float variables that are part of a IntersectionRenderObject.
Definition: intersection_render_object.cpp:129
etsi_its_msgs::displays::IntersectionMovementState
struct etsi_its_msgs::displays::IntersectionMovementState IntersectionMovementState
etsi_its_msgs::displays::IntersectionRenderObject
Definition: intersection_render_object.hpp:64
etsi_its_msgs::displays::IntersectionRenderObject::IntersectionRenderObject
IntersectionRenderObject(etsi_its_mapem_ts_msgs::msg::IntersectionGeometry intersection, bool timestamp_is_present, etsi_its_mapem_ts_msgs::msg::MinuteOfTheYear mapem_stamp, rclcpp::Time receive_time)
Definition: intersection_render_object.cpp:33
etsi_its_msgs::displays::IntersectionRenderObject::lanes
std::vector< IntersectionLane > lanes
Definition: intersection_render_object.hpp:120
etsi_its_msgs::displays::unknown_direction
@ unknown_direction
Definition: intersection_render_object.hpp:41
etsi_its_msgs::displays::egress
@ egress
Definition: intersection_render_object.hpp:41
etsi_its_msgs::displays::IntersectionLane::nodes
std::vector< geometry_msgs::msg::Point > nodes
Definition: intersection_render_object.hpp:48
etsi_its_msgs::displays::IntersectionMovementState::phase_state
etsi_its_spatem_ts_msgs::msg::MovementPhaseState phase_state
Definition: intersection_render_object.hpp:55
etsi_its_msgs::displays::IntersectionRenderObject::getGridConvergenceQuaternion
tf2::Quaternion getGridConvergenceQuaternion()
Return a tf2::Quaternion describing the rotation offset between true-north and grid-north in the UTM ...
Definition: intersection_render_object.cpp:158
etsi_its_msgs::displays::IntersectionRenderObject::movement_states
std::unordered_map< int, IntersectionMovementState > movement_states
Definition: intersection_render_object.hpp:121
etsi_its_msgs::displays::striping
@ striping
Definition: intersection_render_object.hpp:42
etsi_its_msgs::displays::LaneType
LaneType
Definition: intersection_render_object.hpp:42
etsi_its_msgs::displays::IntersectionLane::signal_group_ids
std::vector< uint8_t > signal_group_ids
Definition: intersection_render_object.hpp:49
etsi_its_msgs::displays::ingress
@ ingress
Definition: intersection_render_object.hpp:41
etsi_its_msgs::displays::IntersectionLane
struct etsi_its_msgs::displays::IntersectionLane IntersectionLane
etsi_its_msgs::displays::IntersectionLane::direction
LaneDirection direction
Definition: intersection_render_object.hpp:47
etsi_its_msgs::displays::vehicle
@ vehicle
Definition: intersection_render_object.hpp:42
etsi_its_msgs::displays::IntersectionRenderObject::getAge
double getAge(rclcpp::Time now)
Get age of corresponding MAPEM.
Definition: intersection_render_object.cpp:135
etsi_its_msgs::displays::IntersectionRenderObject::getRefPosition
geometry_msgs::msg::Point getRefPosition()
Get the ref_position object.
Definition: intersection_render_object.cpp:154
etsi_its_msgs::displays::IntersectionRenderObject::removeOutdatedMovemenStates
void removeOutdatedMovemenStates(rclcpp::Time now, double timeout)
Remove outdated MovementStates.
Definition: intersection_render_object.cpp:139
etsi_its_msgs::displays::IntersectionMovementState::signal_group_id
uint8_t signal_group_id
Definition: intersection_render_object.hpp:54
etsi_its_msgs::displays::IntersectionLane::lane_id
uint8_t lane_id
Definition: intersection_render_object.hpp:45
etsi_its_msgs::displays::IntersectionRenderObject::grid_convergence_angle
double grid_convergence_angle
Definition: intersection_render_object.hpp:129
etsi_its_msgs::displays::IntersectionRenderObject::header
std_msgs::msg::Header header
Definition: intersection_render_object.hpp:125
etsi_its_msgs::displays::IntersectionMovementState::header
std_msgs::msg::Header header
Definition: intersection_render_object.hpp:53
etsi_its_msgs::displays::bike_lane
@ bike_lane
Definition: intersection_render_object.hpp:42
etsi_its_msgs::displays::IntersectionRenderObject::layer_ids
std::vector< unsigned int > layer_ids
Definition: intersection_render_object.hpp:127
etsi_its_msgs::displays::IntersectionMovementState::time_change_details
etsi_its_spatem_ts_msgs::msg::TimeChangeDetails::SharedPtr time_change_details
Definition: intersection_render_object.hpp:56
etsi_its_msgs::displays::LaneDirection
LaneDirection
Definition: intersection_render_object.hpp:41
etsi_its_msgs::displays::no_travel
@ no_travel
Definition: intersection_render_object.hpp:41
etsi_its_msgs::displays::IntersectionRenderObject::getHeader
std_msgs::msg::Header getHeader()
Get the header.
Definition: intersection_render_object.cpp:150
etsi_its_msgs::displays::sidewalk
@ sidewalk
Definition: intersection_render_object.hpp:42
etsi_its_msgs::displays::IntersectionRenderObject::ref_point
geometry_msgs::msg::PointStamped ref_point
Definition: intersection_render_object.hpp:128
etsi_its_msgs::displays::IntersectionLane::type
LaneType type
Definition: intersection_render_object.hpp:46
etsi_its_msgs::displays::median
@ median
Definition: intersection_render_object.hpp:42
etsi_its_msgs::displays::IntersectionMovementState
Definition: intersection_render_object.hpp:52
etsi_its_msgs::displays::unknown_type
@ unknown_type
Definition: intersection_render_object.hpp:42
etsi_its_msgs
Definition: cam_display.hpp:51
etsi_its_msgs::displays::tracked_vehicle
@ tracked_vehicle
Definition: intersection_render_object.hpp:42
etsi_its_msgs::displays::IntersectionRenderObject::intersection_id
unsigned int intersection_id
Definition: intersection_render_object.hpp:126
etsi_its_msgs::displays::IntersectionLane
Definition: intersection_render_object.hpp:44


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