1 #ifndef SPECIAL_MESSAGES_H 2 #define SPECIAL_MESSAGES_H 21 return double(sec) + double(nanosec)*1e-9;
38 std::vector<std::pair<std::string, std::string>>
key_value;
40 static const char*
id() {
return "diagnostic_msgs/DiagnosticStatus"; }
46 std::vector<DiagnosticStatus>
status;
48 static const char*
id() {
return "diagnostic_msgs/DiagnosticArray"; }
58 static const char*
id() {
return "geometry_msgs/Vector3"; }
68 static const char*
id() {
return "geometry_msgs/Quaternion"; }
85 static const char*
id() {
return "geometry_msgs/Transform"; }
94 static const char*
id() {
return "geometry_msgs/TransformStamped"; }
101 static const char*
id() {
return "tf2_msgs/TFMessage"; }
113 static const char*
id() {
return "sensor_msgs/JointState"; }
118 #endif // SPECIAL_MESSAGES_H
std::vector< double > velocity
std::vector< std::string > name
std::vector< DiagnosticStatus > status
RPY QuaternionToRPY(Quaternion q)
std::vector< double > effort
std::vector< std::pair< std::string, std::string > > key_value
std::vector< double > position
std::vector< TransformStamped > transforms