cpm_render_object.hpp
Go to the documentation of this file.
1 
25 #include "etsi_its_cpm_ts_msgs/msg/collective_perception_message.hpp"
26 #include <geometry_msgs/msg/point_stamped.hpp>
27 #include <geometry_msgs/msg/pose.hpp>
28 #include <geometry_msgs/msg/vector3.hpp>
29 #include <std_msgs/msg/header.hpp>
30 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
31 
32 #include <tf2/LinearMath/Quaternion.h>
33 #include <etsi_its_msgs_utils/cpm_ts_access.hpp>
34 
35 #include "rviz_common/validate_floats.hpp"
36 
37 namespace etsi_its_msgs
38 {
39 namespace displays
40 {
41 
47 {
48  public:
54  CPMRenderObject(const etsi_its_cpm_ts_msgs::msg::CollectivePerceptionMessage cpm);
55 
60  bool validateFloats();
61 
68  double getAge(const rclcpp::Time now);
69 
70  std_msgs::msg::Header getHeader();
71  uint32_t getStationID();
72  geometry_msgs::msg::PointStamped getReferencePosition();
73 
74  uint8_t getNumberOfObjects();
75  geometry_msgs::msg::Pose getPoseOfObject(const uint8_t idx);
76  geometry_msgs::msg::Vector3 getDimensionsOfObject(const uint8_t idx);
77  geometry_msgs::msg::Vector3 getVelocityOfObject(const uint8_t idx);
78 
79  struct Object {
80  geometry_msgs::msg::Pose pose;
81  geometry_msgs::msg::Vector3 dimensions;
82  geometry_msgs::msg::Vector3 velocity;
83  };
84 
85  private:
86  std_msgs::msg::Header header_;
87  uint32_t station_id_;
88  geometry_msgs::msg::PointStamped reference_position_;
89  std::vector<Object> objects_;
90 };
91 
92 } // namespace displays
93 } // namespace etsi_its_msgs
etsi_its_msgs::displays::CPMRenderObject::getHeader
std_msgs::msg::Header getHeader()
Definition: cpm_render_object.cpp:68
etsi_its_msgs::displays::CPMRenderObject::Object::dimensions
geometry_msgs::msg::Vector3 dimensions
Definition: cpm_render_object.hpp:81
etsi_its_msgs::displays::CPMRenderObject::getVelocityOfObject
geometry_msgs::msg::Vector3 getVelocityOfObject(const uint8_t idx)
Definition: cpm_render_object.cpp:78
etsi_its_msgs::displays::CPMRenderObject::Object::velocity
geometry_msgs::msg::Vector3 velocity
Definition: cpm_render_object.hpp:82
etsi_its_msgs::displays::CPMRenderObject::station_id_
uint32_t station_id_
Definition: cpm_render_object.hpp:87
etsi_its_msgs::displays::CPMRenderObject::getReferencePosition
geometry_msgs::msg::PointStamped getReferencePosition()
Definition: cpm_render_object.cpp:72
etsi_its_msgs::displays::CPMRenderObject::getNumberOfObjects
uint8_t getNumberOfObjects()
Definition: cpm_render_object.cpp:80
etsi_its_msgs::displays::CPMRenderObject::getAge
double getAge(const rclcpp::Time now)
Get age of CPM-object.
Definition: cpm_render_object.cpp:66
etsi_its_msgs::displays::CPMRenderObject::getStationID
uint32_t getStationID()
Definition: cpm_render_object.cpp:70
etsi_its_msgs::displays::CPMRenderObject::reference_position_
geometry_msgs::msg::PointStamped reference_position_
Definition: cpm_render_object.hpp:88
etsi_its_msgs::displays::CPMRenderObject::validateFloats
bool validateFloats()
This function validates all float variables that are part of a CPMRenderObject.
Definition: cpm_render_object.cpp:56
etsi_its_msgs::displays::CPMRenderObject::Object
Definition: cpm_render_object.hpp:79
etsi_its_msgs::displays::CPMRenderObject::header_
std_msgs::msg::Header header_
Definition: cpm_render_object.hpp:86
etsi_its_msgs::displays::CPMRenderObject
This class is used to render a CPM object in RViz.
Definition: cpm_render_object.hpp:46
etsi_its_msgs::displays::CPMRenderObject::objects_
std::vector< Object > objects_
Definition: cpm_render_object.hpp:89
etsi_its_msgs::displays::CPMRenderObject::Object::pose
geometry_msgs::msg::Pose pose
Definition: cpm_render_object.hpp:80
etsi_its_msgs::displays::CPMRenderObject::getDimensionsOfObject
geometry_msgs::msg::Vector3 getDimensionsOfObject(const uint8_t idx)
Definition: cpm_render_object.cpp:76
etsi_its_msgs
Definition: cam_display.hpp:51
etsi_its_msgs::displays::CPMRenderObject::getPoseOfObject
geometry_msgs::msg::Pose getPoseOfObject(const uint8_t idx)
Definition: cpm_render_object.cpp:74
etsi_its_msgs::displays::CPMRenderObject::CPMRenderObject
CPMRenderObject(const etsi_its_cpm_ts_msgs::msg::CollectivePerceptionMessage cpm)
Construct a new CPMRenderObject object from a CPM message.
Definition: cpm_render_object.cpp:30


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