cam_render_object.hpp
Go to the documentation of this file.
1 
25 #include "etsi_its_cam_msgs/msg/cam.hpp"
26 #include <geometry_msgs/msg/pose.hpp>
27 #include <geometry_msgs/msg/vector3.hpp>
28 #include <std_msgs/msg/header.hpp>
29 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
30 
31 #include <tf2/LinearMath/Quaternion.h>
32 #include <etsi_its_msgs_utils/cam_access.hpp>
33 
34 #include "rviz_common/validate_floats.hpp"
35 
36 namespace etsi_its_msgs
37 {
38 namespace displays
39 {
40 
46 {
47  public:
48  CAMRenderObject(etsi_its_cam_msgs::msg::CAM cam, rclcpp::Time receive_time, uint16_t n_leap_seconds=etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.rbegin()->second);
49 
54  bool validateFloats();
55 
62  double getAge(rclcpp::Time now);
63 
69  std_msgs::msg::Header getHeader();
70 
76  uint32_t getStationID();
77 
83  int getStationType();
84 
90  geometry_msgs::msg::Pose getPose();
91 
97  geometry_msgs::msg::Vector3 getDimensions();
98 
104  double getSpeed();
105 
106  private:
107  // member variables
108  std_msgs::msg::Header header;
109  uint32_t station_id;
111  geometry_msgs::msg::Pose pose;
112  geometry_msgs::msg::Vector3 dimensions;
113  double speed;
114 
115 };
116 
117 } // namespace displays
118 } // namespace etsi_its_msgs
etsi_its_msgs::displays::CAMRenderObject::getAge
double getAge(rclcpp::Time now)
Get age of CAM-object.
Definition: cam_render_object.cpp:67
etsi_its_msgs::displays::CAMRenderObject::validateFloats
bool validateFloats()
This function validates all float variables that are part of a CAMRenderObject.
Definition: cam_render_object.cpp:59
etsi_its_msgs::displays::CAMRenderObject::station_id
uint32_t station_id
Definition: cam_render_object.hpp:109
etsi_its_msgs::displays::CAMRenderObject
Definition: cam_render_object.hpp:45
etsi_its_msgs::displays::CAMRenderObject::getHeader
std_msgs::msg::Header getHeader()
Get header of CAM-object.
Definition: cam_render_object.cpp:71
etsi_its_msgs::displays::CAMRenderObject::getStationType
int getStationType()
Get the StationType of CAM-object.
Definition: cam_render_object.cpp:79
etsi_its_msgs::displays::CAMRenderObject::getSpeed
double getSpeed()
Get speed of CAM-object.
Definition: cam_render_object.cpp:92
etsi_its_msgs::displays::CAMRenderObject::getPose
geometry_msgs::msg::Pose getPose()
Get pose of CAM-object.
Definition: cam_render_object.cpp:83
etsi_its_msgs::displays::CAMRenderObject::CAMRenderObject
CAMRenderObject(etsi_its_cam_msgs::msg::CAM cam, rclcpp::Time receive_time, uint16_t n_leap_seconds=etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.rbegin() ->second)
Definition: cam_render_object.cpp:32
etsi_its_msgs::displays::CAMRenderObject::dimensions
geometry_msgs::msg::Vector3 dimensions
Definition: cam_render_object.hpp:112
etsi_its_msgs::displays::CAMRenderObject::station_type
int station_type
Definition: cam_render_object.hpp:110
etsi_its_msgs::displays::CAMRenderObject::getStationID
uint32_t getStationID()
Get the StationID of CAM-object.
Definition: cam_render_object.cpp:75
etsi_its_msgs::displays::CAMRenderObject::speed
double speed
Definition: cam_render_object.hpp:113
etsi_its_msgs::displays::CAMRenderObject::pose
geometry_msgs::msg::Pose pose
Definition: cam_render_object.hpp:111
etsi_its_msgs::displays::CAMRenderObject::header
std_msgs::msg::Header header
Definition: cam_render_object.hpp:108
etsi_its_msgs
Definition: cam_display.hpp:51
etsi_its_msgs::displays::CAMRenderObject::getDimensions
geometry_msgs::msg::Vector3 getDimensions()
Get dimensions of CAM-Object.
Definition: cam_render_object.cpp:87


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