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 
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 //--------------------
33 {
34  uint8_t level;
35  std::string name;
36  std::string message;
37  std::string hardware_id;
38  std::vector<std::pair<std::string, std::string>> key_value;
39 
40  static const char* id() { return "diagnostic_msgs/DiagnosticStatus"; }
41 };
42 
44 {
46  std::vector<DiagnosticStatus> status;
47 
48  static const char* id() { return "diagnostic_msgs/DiagnosticArray"; }
49 };
50 
51 //--------------------
52 struct Vector3
53 {
54  double x;
55  double y;
56  double z;
57 
58  static const char* id() { return "geometry_msgs/Vector3"; }
59 };
60 
61 struct Quaternion
62 {
63  double x;
64  double y;
65  double z;
66  double w;
67 
68  static const char* id() { return "geometry_msgs/Quaternion"; }
69 };
70 
71 struct RPY
72 {
73  double roll;
74  double pitch;
75  double yaw;
76 };
77 
79 
80 struct Transform
81 {
84 
85  static const char* id() { return "geometry_msgs/Transform"; }
86 };
87 
89 {
91  std::string child_frame_id;
93 
94  static const char* id() { return "geometry_msgs/TransformStamped"; }
95 };
96 
97 struct TFMessage
98 {
99  std::vector<TransformStamped> transforms;
100 
101  static const char* id() { return "tf2_msgs/TFMessage"; }
102 };
103 //--------------------
104 
106 {
108  std::vector<std::string> name;
109  std::vector<double> position;
110  std::vector<double> velocity;
111  std::vector<double> effort;
112 
113  static const char* id() { return "sensor_msgs/JointState"; }
114 };
115 
116 }
117 
118 #endif // SPECIAL_MESSAGES_H
static const char * id()
double toSec() const
std::vector< double > velocity
std::vector< std::string > name
PJ::Msg::Time stamp
std::vector< DiagnosticStatus > status
RPY QuaternionToRPY(Quaternion q)
static const char * id()
static const char * id()
static const char * id()
static const char * id()
std::vector< double > effort
static const char * id()
std::string frame_id
static const char * id()
std::vector< std::pair< std::string, std::string > > key_value
std::vector< double > position
std::vector< TransformStamped > transforms
static const char * id()


plotjuggler
Author(s): Davide Faconti
autogenerated on Mon Jun 19 2023 03:12:53