special_messages.h
Go to the documentation of this file.
1 #ifndef SPECIAL_MESSAGES_H
2 #define SPECIAL_MESSAGES_H
3 
4 // These messages are exact equivalents of ROS messages
5 
6 #include <array>
7 #include <vector>
8 #include <string>
9 #include <cstdint>
10 
11 namespace PJ::Msg
12 {
13 
14 struct Time
15 {
16  uint32_t sec;
17  uint32_t nanosec;
18 
19  double toSec() const
20  {
21  return double(sec) + double(nanosec) * 1e-9;
22  }
23 };
24 
25 struct Header
26 {
27  uint32_t seq;
29  std::string frame_id;
30 };
31 
32 struct Empty
33 {
34  static const char* id()
35  {
36  return "std_msgs/Empty";
37  }
38 };
39 
40 //--------------------
42 {
43  uint8_t level;
44  std::string name;
45  std::string message;
46  std::string hardware_id;
47  std::vector<std::pair<std::string, std::string>> key_value;
48 
49  static const char* id()
50  {
51  return "diagnostic_msgs/DiagnosticStatus";
52  }
53 };
54 
56 {
58  std::vector<DiagnosticStatus> status;
59 
60  static const char* id()
61  {
62  return "diagnostic_msgs/DiagnosticArray";
63  }
64 };
65 
66 //--------------------
67 struct Vector3
68 {
69  double x;
70  double y;
71  double z;
72 
73  static const char* id()
74  {
75  return "geometry_msgs/Vector3";
76  }
77 };
78 
79 struct Point
80 {
81  double x;
82  double y;
83  double z;
84 
85  static const char* id()
86  {
87  return "geometry_msgs/Point";
88  }
89 };
90 
91 struct Quaternion
92 {
93  double x;
94  double y;
95  double z;
96  double w;
97 
98  static const char* id()
99  {
100  return "geometry_msgs/Quaternion";
101  }
102 };
103 
104 struct RPY
105 {
106  double roll;
107  double pitch;
108  double yaw;
109 };
110 
112 
113 struct Transform
114 {
117 
118  static const char* id()
119  {
120  return "geometry_msgs/Transform";
121  }
122 };
123 
125 {
127  std::string child_frame_id;
129 
130  static const char* id()
131  {
132  return "geometry_msgs/TransformStamped";
133  }
134 };
135 
136 struct Pose
137 {
140 
141  static const char* id()
142  {
143  return "geometry_msgs/Pose";
144  }
145 };
146 
148 {
151 
152  static const char* id()
153  {
154  return "geometry_msgs/PoseStamped";
155  }
156 };
157 
159 {
161  std::array<double, 36> covariance;
162 
163  static const char* id()
164  {
165  return "geometry_msgs/PoseWithCovariance";
166  }
167 };
168 
169 struct Twist
170 {
173 
174  static const char* id()
175  {
176  return "geometry_msgs/Twist";
177  }
178 };
179 
181 {
183  std::array<double, 36> covariance;
184 
185  static const char* id()
186  {
187  return "geometry_msgs/TwistWithCovariance";
188  }
189 };
190 
191 struct TFMessage
192 {
193  std::vector<TransformStamped> transforms;
194 
195  static const char* id()
196  {
197  return "tf2_msgs/TFMessage";
198  }
199 };
200 //--------------------
201 
202 struct Imu
203 {
206  std::array<double, 9> orientation_covariance;
208  std::array<double, 9> angular_velocity_covariance;
210  std::array<double, 9> linear_acceleration_covariance;
211 
212  static const char* id()
213  {
214  return "sensor_msgs/Imu";
215  }
216 };
217 //--------------------
218 struct Odometry
219 {
223 
224  static const char* id()
225  {
226  return "nav_msgs/Odometry";
227  }
228 };
229 
230 //--------------------
231 
233 {
235  std::vector<std::string> name;
236  std::vector<double> position;
237  std::vector<double> velocity;
238  std::vector<double> effort;
239 
240  static const char* id()
241  {
242  return "sensor_msgs/JointState";
243  }
244 };
245 
246 //--------------------
247 
249 {
250  // no need to save any additional information
251 
252  static const char* id()
253  {
254  return "data_tamer_msgs/Schemas";
255  }
256 };
257 
259 {
260  std::string prefix;
261  uint64_t timestamp_nsec;
262  uint64_t schema_hash;
263  std::vector<uint8_t> active_mask;
264  std::vector<uint8_t> payload;
265 
266  static const char* id()
267  {
268  return "data_tamer_msgs/Snapshot";
269  }
270 };
271 
272 //--------------------
273 
275 {
277  std::vector<std::string> names;
278  uint32_t names_version;
279 
280  static const char* id()
281  {
282  return "pal_statistics_msgs/StatisticsNames";
283  }
284 };
285 
287 {
289  std::vector<double> names;
290  uint32_t names_version;
291 
292  static const char* id()
293  {
294  return "pal_statistics_msgs/StatisticsValues";
295  }
296 };
297 } // namespace PJ::Msg
298 
299 #endif // SPECIAL_MESSAGES_H
PJ::Msg::TwistWithCovariance::covariance
std::array< double, 36 > covariance
Definition: special_messages.h:183
PJ::Msg::Vector3::z
double z
Definition: special_messages.h:71
PJ::Msg::Time
Definition: special_messages.h:14
PJ::Msg::Transform::translation
Point translation
Definition: special_messages.h:115
PJ::Msg::Imu
Definition: special_messages.h:202
PJ::Msg::Transform::id
static const char * id()
Definition: special_messages.h:118
PJ::Msg::DiagnosticStatus::message
std::string message
Definition: special_messages.h:45
PJ::Msg::Header::stamp
PJ::Msg::Time stamp
Definition: special_messages.h:28
PJ::Msg::DiagnosticArray::status
std::vector< DiagnosticStatus > status
Definition: special_messages.h:58
PJ::Msg::JointState::effort
std::vector< double > effort
Definition: special_messages.h:238
PJ::Msg::TransformStamped::child_frame_id
std::string child_frame_id
Definition: special_messages.h:127
PJ::Msg::Point
Definition: special_messages.h:79
PJ::Msg::TransformStamped::id
static const char * id()
Definition: special_messages.h:130
PJ::Msg::Imu::angular_velocity
Vector3 angular_velocity
Definition: special_messages.h:207
PJ::Msg::PalStatisticsValues
Definition: special_messages.h:286
PJ::Msg::DataTamerSnapshot
Definition: special_messages.h:258
PJ::Msg::Point::id
static const char * id()
Definition: special_messages.h:85
PJ::Msg::JointState::id
static const char * id()
Definition: special_messages.h:240
PJ::Msg::Quaternion::w
double w
Definition: special_messages.h:96
PJ::Msg::DataTamerSnapshot::timestamp_nsec
uint64_t timestamp_nsec
Definition: special_messages.h:261
PJ::Msg::TwistWithCovariance::id
static const char * id()
Definition: special_messages.h:185
PJ::Msg::DiagnosticStatus::key_value
std::vector< std::pair< std::string, std::string > > key_value
Definition: special_messages.h:47
PJ::Msg::Twist::angular
Vector3 angular
Definition: special_messages.h:172
PJ::Msg::Imu::header
Header header
Definition: special_messages.h:204
PJ::Msg::TransformStamped::transform
Transform transform
Definition: special_messages.h:128
PJ::Msg::Twist::id
static const char * id()
Definition: special_messages.h:174
PJ::Msg::TFMessage::id
static const char * id()
Definition: special_messages.h:195
PJ::Msg::Odometry::pose
PoseWithCovariance pose
Definition: special_messages.h:221
PJ::Msg::Point::z
double z
Definition: special_messages.h:83
PJ::Msg::Pose
Definition: special_messages.h:136
PJ::Msg::RPY::roll
double roll
Definition: special_messages.h:106
PJ::Msg::Empty::id
static const char * id()
Definition: special_messages.h:34
PJ::Msg::JointState::position
std::vector< double > position
Definition: special_messages.h:236
PJ::Msg::Twist::linear
Vector3 linear
Definition: special_messages.h:171
PJ::Msg::TwistWithCovariance
Definition: special_messages.h:180
PJ::Msg::PoseWithCovariance::id
static const char * id()
Definition: special_messages.h:163
PJ::Msg::Odometry::twist
TwistWithCovariance twist
Definition: special_messages.h:222
PJ::Msg::JointState::header
Header header
Definition: special_messages.h:234
PJ::Msg::Vector3
Definition: special_messages.h:67
PJ::Msg::Transform
Definition: special_messages.h:113
PJ::Msg::PalStatisticsNames::id
static const char * id()
Definition: special_messages.h:280
PJ::Msg::JointState::name
std::vector< std::string > name
Definition: special_messages.h:235
PJ::Msg::TwistWithCovariance::twist
Twist twist
Definition: special_messages.h:182
PJ::Msg::Vector3::x
double x
Definition: special_messages.h:69
PJ::Msg::Quaternion::id
static const char * id()
Definition: special_messages.h:98
PJ::Msg::DiagnosticStatus
Definition: special_messages.h:41
PJ::Msg::DataTamerSnapshot::id
static const char * id()
Definition: special_messages.h:266
PJ::Msg::Time::nanosec
uint32_t nanosec
Definition: special_messages.h:17
PJ::Msg::PalStatisticsValues::id
static const char * id()
Definition: special_messages.h:292
PJ::Msg::PalStatisticsValues::header
Header header
Definition: special_messages.h:288
PJ::Msg::Imu::orientation
Quaternion orientation
Definition: special_messages.h:205
PJ::Msg::Empty
Definition: special_messages.h:32
PJ::Msg::RPY
Definition: special_messages.h:104
PJ::Msg::Odometry::header
Header header
Definition: special_messages.h:220
PJ::Msg::Header::seq
uint32_t seq
Definition: special_messages.h:27
PJ::Msg::TransformStamped
Definition: special_messages.h:124
PJ::Msg::Quaternion::x
double x
Definition: special_messages.h:93
PJ::Msg::DiagnosticStatus::hardware_id
std::string hardware_id
Definition: special_messages.h:46
PJ::Msg::DiagnosticStatus::id
static const char * id()
Definition: special_messages.h:49
PJ::Msg::PalStatisticsNames::names
std::vector< std::string > names
Definition: special_messages.h:277
PJ::Msg::Transform::rotation
Quaternion rotation
Definition: special_messages.h:116
PJ::Msg::TFMessage
Definition: special_messages.h:191
PJ::Msg::Point::y
double y
Definition: special_messages.h:82
PJ::Msg::RPY::pitch
double pitch
Definition: special_messages.h:107
PJ::Msg::Time::toSec
double toSec() const
Definition: special_messages.h:19
PJ::Msg::PalStatisticsNames
Definition: special_messages.h:274
PJ::Msg::Odometry
Definition: special_messages.h:218
PJ::Msg::Time::sec
uint32_t sec
Definition: special_messages.h:16
PJ::Msg::DataTamerSchemas
Definition: special_messages.h:248
PJ::Msg::RPY::yaw
double yaw
Definition: special_messages.h:108
PJ::Msg::PalStatisticsNames::names_version
uint32_t names_version
Definition: special_messages.h:278
PJ::Msg
Definition: special_messages.h:11
PJ::Msg::PoseStamped::pose
Pose pose
Definition: special_messages.h:150
PJ::Msg::Pose::orientation
Quaternion orientation
Definition: special_messages.h:139
PJ::Msg::DataTamerSnapshot::prefix
std::string prefix
Definition: special_messages.h:260
PJ::Msg::PoseStamped::header
Header header
Definition: special_messages.h:149
PJ::Msg::PalStatisticsValues::names
std::vector< double > names
Definition: special_messages.h:289
PJ::Msg::Imu::linear_acceleration
Vector3 linear_acceleration
Definition: special_messages.h:209
PJ::Msg::DiagnosticArray
Definition: special_messages.h:55
PJ::Msg::Vector3::y
double y
Definition: special_messages.h:70
PJ::Msg::Imu::orientation_covariance
std::array< double, 9 > orientation_covariance
Definition: special_messages.h:206
PJ::Msg::QuaternionToRPY
RPY QuaternionToRPY(Quaternion q)
Definition: special_messages.cpp:4
PJ::Msg::PoseWithCovariance::pose
Pose pose
Definition: special_messages.h:160
PJ::Msg::TFMessage::transforms
std::vector< TransformStamped > transforms
Definition: special_messages.h:193
PJ::Msg::PoseWithCovariance::covariance
std::array< double, 36 > covariance
Definition: special_messages.h:161
PJ::Msg::JointState
Definition: special_messages.h:232
PJ::Msg::DataTamerSnapshot::payload
std::vector< uint8_t > payload
Definition: special_messages.h:264
PJ::Msg::PoseStamped
Definition: special_messages.h:147
PJ::Msg::Pose::position
Vector3 position
Definition: special_messages.h:138
PJ::Msg::JointState::velocity
std::vector< double > velocity
Definition: special_messages.h:237
PJ::Msg::Imu::linear_acceleration_covariance
std::array< double, 9 > linear_acceleration_covariance
Definition: special_messages.h:210
PJ::Msg::Header::frame_id
std::string frame_id
Definition: special_messages.h:29
PJ::Msg::DiagnosticStatus::level
uint8_t level
Definition: special_messages.h:43
PJ::Msg::Point::x
double x
Definition: special_messages.h:81
PJ::Msg::PalStatisticsNames::header
Header header
Definition: special_messages.h:276
PJ::Msg::Imu::angular_velocity_covariance
std::array< double, 9 > angular_velocity_covariance
Definition: special_messages.h:208
PJ::Msg::PalStatisticsValues::names_version
uint32_t names_version
Definition: special_messages.h:290
PJ::Msg::Imu::id
static const char * id()
Definition: special_messages.h:212
PJ::Msg::Quaternion::z
double z
Definition: special_messages.h:95
PJ::Msg::Header
Definition: special_messages.h:25
PJ::Msg::PoseWithCovariance
Definition: special_messages.h:158
PJ::Msg::DiagnosticArray::header
Header header
Definition: special_messages.h:57
PJ::Msg::TransformStamped::header
Header header
Definition: special_messages.h:126
PJ::Msg::Quaternion::y
double y
Definition: special_messages.h:94
PJ::Msg::DiagnosticArray::id
static const char * id()
Definition: special_messages.h:60
PJ::Msg::Vector3::id
static const char * id()
Definition: special_messages.h:73
PJ::Msg::DiagnosticStatus::name
std::string name
Definition: special_messages.h:44
PJ::Msg::PoseStamped::id
static const char * id()
Definition: special_messages.h:152
PJ::Msg::Pose::id
static const char * id()
Definition: special_messages.h:141
PJ::Msg::Quaternion
Definition: special_messages.h:91
PJ::Msg::DataTamerSnapshot::active_mask
std::vector< uint8_t > active_mask
Definition: special_messages.h:263
PJ::Msg::Twist
Definition: special_messages.h:169
PJ::Msg::DataTamerSchemas::id
static const char * id()
Definition: special_messages.h:252
PJ::Msg::Odometry::id
static const char * id()
Definition: special_messages.h:224
PJ::Msg::DataTamerSnapshot::schema_hash
uint64_t schema_hash
Definition: special_messages.h:262


plotjuggler
Author(s): Davide Faconti
autogenerated on Mon Nov 11 2024 03:23:47