YARP
Yet Another Robot Platform
MultiDOFJointState.h
Go to the documentation of this file.
1 /*
2  * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
3  * SPDX-License-Identifier: BSD-3-Clause
4  */
5 
6 // This is an automatically generated file.
7 
8 // Generated from the following "sensor_msgs/MultiDOFJointState" msg definition:
9 // # Representation of state for joints with multiple degrees of freedom,
10 // # following the structure of JointState.
11 // #
12 // # It is assumed that a joint in a system corresponds to a transform that gets applied
13 // # along the kinematic chain. For example, a planar joint (as in URDF) is 3DOF (x, y, yaw)
14 // # and those 3DOF can be expressed as a transformation matrix, and that transformation
15 // # matrix can be converted back to (x, y, yaw)
16 // #
17 // # Each joint is uniquely identified by its name
18 // # The header specifies the time at which the joint states were recorded. All the joint states
19 // # in one message have to be recorded at the same time.
20 // #
21 // # This message consists of a multiple arrays, one for each part of the joint state.
22 // # The goal is to make each of the fields optional. When e.g. your joints have no
23 // # wrench associated with them, you can leave the wrench array empty.
24 // #
25 // # All arrays in this message should have the same size, or be empty.
26 // # This is the only way to uniquely associate the joint name with the correct
27 // # states.
28 //
29 // Header header
30 //
31 // string[] joint_names
32 // geometry_msgs/Transform[] transforms
33 // geometry_msgs/Twist[] twist
34 // geometry_msgs/Wrench[] wrench
35 // Instances of this class can be read and written with YARP ports,
36 // using a ROS-compatible format.
37 
38 #ifndef YARP_ROSMSG_sensor_msgs_MultiDOFJointState_h
39 #define YARP_ROSMSG_sensor_msgs_MultiDOFJointState_h
40 
41 #include <yarp/os/Wire.h>
42 #include <yarp/os/Type.h>
43 #include <yarp/os/idl/WireTypes.h>
44 #include <string>
45 #include <vector>
50 
51 namespace yarp {
52 namespace rosmsg {
53 namespace sensor_msgs {
54 
56 {
57 public:
59  std::vector<std::string> joint_names;
60  std::vector<yarp::rosmsg::geometry_msgs::Transform> transforms;
61  std::vector<yarp::rosmsg::geometry_msgs::Twist> twist;
62  std::vector<yarp::rosmsg::geometry_msgs::Wrench> wrench;
63 
65  header(),
66  joint_names(),
67  transforms(),
68  twist(),
69  wrench()
70  {
71  }
72 
73  void clear()
74  {
75  // *** header ***
76  header.clear();
77 
78  // *** joint_names ***
79  joint_names.clear();
80 
81  // *** transforms ***
82  transforms.clear();
83 
84  // *** twist ***
85  twist.clear();
86 
87  // *** wrench ***
88  wrench.clear();
89  }
90 
91  bool readBare(yarp::os::ConnectionReader& connection) override
92  {
93  // *** header ***
94  if (!header.read(connection)) {
95  return false;
96  }
97 
98  // *** joint_names ***
99  int len = connection.expectInt32();
100  joint_names.resize(len);
101  for (int i=0; i<len; i++) {
102  int len2 = connection.expectInt32();
103  joint_names[i].resize(len2);
104  if (!connection.expectBlock((char*)joint_names[i].c_str(), len2)) {
105  return false;
106  }
107  }
108 
109  // *** transforms ***
110  len = connection.expectInt32();
111  transforms.resize(len);
112  for (int i=0; i<len; i++) {
113  if (!transforms[i].read(connection)) {
114  return false;
115  }
116  }
117 
118  // *** twist ***
119  len = connection.expectInt32();
120  twist.resize(len);
121  for (int i=0; i<len; i++) {
122  if (!twist[i].read(connection)) {
123  return false;
124  }
125  }
126 
127  // *** wrench ***
128  len = connection.expectInt32();
129  wrench.resize(len);
130  for (int i=0; i<len; i++) {
131  if (!wrench[i].read(connection)) {
132  return false;
133  }
134  }
135 
136  return !connection.isError();
137  }
138 
139  bool readBottle(yarp::os::ConnectionReader& connection) override
140  {
141  connection.convertTextMode();
142  yarp::os::idl::WireReader reader(connection);
143  if (!reader.readListHeader(5)) {
144  return false;
145  }
146 
147  // *** header ***
148  if (!header.read(connection)) {
149  return false;
150  }
151 
152  // *** joint_names ***
153  if (connection.expectInt32() != (BOTTLE_TAG_LIST|BOTTLE_TAG_STRING)) {
154  return false;
155  }
156  int len = connection.expectInt32();
157  joint_names.resize(len);
158  for (int i=0; i<len; i++) {
159  int len2 = connection.expectInt32();
160  joint_names[i].resize(len2);
161  if (!connection.expectBlock((char*)joint_names[i].c_str(), len2)) {
162  return false;
163  }
164  }
165 
166  // *** transforms ***
167  if (connection.expectInt32() != BOTTLE_TAG_LIST) {
168  return false;
169  }
170  len = connection.expectInt32();
171  transforms.resize(len);
172  for (int i=0; i<len; i++) {
173  if (!transforms[i].read(connection)) {
174  return false;
175  }
176  }
177 
178  // *** twist ***
179  if (connection.expectInt32() != BOTTLE_TAG_LIST) {
180  return false;
181  }
182  len = connection.expectInt32();
183  twist.resize(len);
184  for (int i=0; i<len; i++) {
185  if (!twist[i].read(connection)) {
186  return false;
187  }
188  }
189 
190  // *** wrench ***
191  if (connection.expectInt32() != BOTTLE_TAG_LIST) {
192  return false;
193  }
194  len = connection.expectInt32();
195  wrench.resize(len);
196  for (int i=0; i<len; i++) {
197  if (!wrench[i].read(connection)) {
198  return false;
199  }
200  }
201 
202  return !connection.isError();
203  }
204 
206  bool read(yarp::os::ConnectionReader& connection) override
207  {
208  return (connection.isBareMode() ? readBare(connection)
209  : readBottle(connection));
210  }
211 
212  bool writeBare(yarp::os::ConnectionWriter& connection) const override
213  {
214  // *** header ***
215  if (!header.write(connection)) {
216  return false;
217  }
218 
219  // *** joint_names ***
220  connection.appendInt32(joint_names.size());
221  for (size_t i=0; i<joint_names.size(); i++) {
222  connection.appendInt32(joint_names[i].length());
223  connection.appendExternalBlock((char*)joint_names[i].c_str(), joint_names[i].length());
224  }
225 
226  // *** transforms ***
227  connection.appendInt32(transforms.size());
228  for (size_t i=0; i<transforms.size(); i++) {
229  if (!transforms[i].write(connection)) {
230  return false;
231  }
232  }
233 
234  // *** twist ***
235  connection.appendInt32(twist.size());
236  for (size_t i=0; i<twist.size(); i++) {
237  if (!twist[i].write(connection)) {
238  return false;
239  }
240  }
241 
242  // *** wrench ***
243  connection.appendInt32(wrench.size());
244  for (size_t i=0; i<wrench.size(); i++) {
245  if (!wrench[i].write(connection)) {
246  return false;
247  }
248  }
249 
250  return !connection.isError();
251  }
252 
253  bool writeBottle(yarp::os::ConnectionWriter& connection) const override
254  {
255  connection.appendInt32(BOTTLE_TAG_LIST);
256  connection.appendInt32(5);
257 
258  // *** header ***
259  if (!header.write(connection)) {
260  return false;
261  }
262 
263  // *** joint_names ***
265  connection.appendInt32(joint_names.size());
266  for (size_t i=0; i<joint_names.size(); i++) {
267  connection.appendInt32(joint_names[i].length());
268  connection.appendExternalBlock((char*)joint_names[i].c_str(), joint_names[i].length());
269  }
270 
271  // *** transforms ***
272  connection.appendInt32(BOTTLE_TAG_LIST);
273  connection.appendInt32(transforms.size());
274  for (size_t i=0; i<transforms.size(); i++) {
275  if (!transforms[i].write(connection)) {
276  return false;
277  }
278  }
279 
280  // *** twist ***
281  connection.appendInt32(BOTTLE_TAG_LIST);
282  connection.appendInt32(twist.size());
283  for (size_t i=0; i<twist.size(); i++) {
284  if (!twist[i].write(connection)) {
285  return false;
286  }
287  }
288 
289  // *** wrench ***
290  connection.appendInt32(BOTTLE_TAG_LIST);
291  connection.appendInt32(wrench.size());
292  for (size_t i=0; i<wrench.size(); i++) {
293  if (!wrench[i].write(connection)) {
294  return false;
295  }
296  }
297 
298  connection.convertTextMode();
299  return !connection.isError();
300  }
301 
303  bool write(yarp::os::ConnectionWriter& connection) const override
304  {
305  return (connection.isBareMode() ? writeBare(connection)
306  : writeBottle(connection));
307  }
308 
309  // This class will serialize ROS style or YARP style depending on protocol.
310  // If you need to force a serialization style, use one of these classes:
313 
314  // The name for this message, ROS will need this
315  static constexpr const char* typeName = "sensor_msgs/MultiDOFJointState";
316 
317  // The checksum for this message, ROS will need this
318  static constexpr const char* typeChecksum = "690f272f0640d2631c305eeb8301e59d";
319 
320  // The source text for this message, ROS will need this
321  static constexpr const char* typeText = "\
322 # Representation of state for joints with multiple degrees of freedom, \n\
323 # following the structure of JointState.\n\
324 #\n\
325 # It is assumed that a joint in a system corresponds to a transform that gets applied \n\
326 # along the kinematic chain. For example, a planar joint (as in URDF) is 3DOF (x, y, yaw)\n\
327 # and those 3DOF can be expressed as a transformation matrix, and that transformation\n\
328 # matrix can be converted back to (x, y, yaw)\n\
329 #\n\
330 # Each joint is uniquely identified by its name\n\
331 # The header specifies the time at which the joint states were recorded. All the joint states\n\
332 # in one message have to be recorded at the same time.\n\
333 #\n\
334 # This message consists of a multiple arrays, one for each part of the joint state. \n\
335 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
336 # wrench associated with them, you can leave the wrench array empty. \n\
337 #\n\
338 # All arrays in this message should have the same size, or be empty.\n\
339 # This is the only way to uniquely associate the joint name with the correct\n\
340 # states.\n\
341 \n\
342 Header header\n\
343 \n\
344 string[] joint_names\n\
345 geometry_msgs/Transform[] transforms\n\
346 geometry_msgs/Twist[] twist\n\
347 geometry_msgs/Wrench[] wrench\n\
348 \n\
349 ================================================================================\n\
350 MSG: std_msgs/Header\n\
351 # Standard metadata for higher-level stamped data types.\n\
352 # This is generally used to communicate timestamped data \n\
353 # in a particular coordinate frame.\n\
354 # \n\
355 # sequence ID: consecutively increasing ID \n\
356 uint32 seq\n\
357 #Two-integer timestamp that is expressed as:\n\
358 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
359 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
360 # time-handling sugar is provided by the client library\n\
361 time stamp\n\
362 #Frame this data is associated with\n\
363 # 0: no frame\n\
364 # 1: global frame\n\
365 string frame_id\n\
366 \n\
367 ================================================================================\n\
368 MSG: geometry_msgs/Transform\n\
369 # This represents the transform between two coordinate frames in free space.\n\
370 \n\
371 Vector3 translation\n\
372 Quaternion rotation\n\
373 \n\
374 ================================================================================\n\
375 MSG: geometry_msgs/Vector3\n\
376 # This represents a vector in free space. \n\
377 # It is only meant to represent a direction. Therefore, it does not\n\
378 # make sense to apply a translation to it (e.g., when applying a \n\
379 # generic rigid transformation to a Vector3, tf2 will only apply the\n\
380 # rotation). If you want your data to be translatable too, use the\n\
381 # geometry_msgs/Point message instead.\n\
382 \n\
383 float64 x\n\
384 float64 y\n\
385 float64 z\n\
386 ================================================================================\n\
387 MSG: geometry_msgs/Quaternion\n\
388 # This represents an orientation in free space in quaternion form.\n\
389 \n\
390 float64 x\n\
391 float64 y\n\
392 float64 z\n\
393 float64 w\n\
394 \n\
395 ================================================================================\n\
396 MSG: geometry_msgs/Twist\n\
397 # This expresses velocity in free space broken into its linear and angular parts.\n\
398 Vector3 linear\n\
399 Vector3 angular\n\
400 \n\
401 ================================================================================\n\
402 MSG: geometry_msgs/Wrench\n\
403 # This represents force in free space, separated into\n\
404 # its linear and angular parts.\n\
405 Vector3 force\n\
406 Vector3 torque\n\
407 ";
408 
409  yarp::os::Type getType() const override
410  {
412  typ.addProperty("md5sum", yarp::os::Value(typeChecksum));
413  typ.addProperty("message_definition", yarp::os::Value(typeText));
414  return typ;
415  }
416 };
417 
418 } // namespace sensor_msgs
419 } // namespace rosmsg
420 } // namespace yarp
421 
422 #endif // YARP_ROSMSG_sensor_msgs_MultiDOFJointState_h
#define BOTTLE_TAG_STRING
Definition: Bottle.h:26
#define BOTTLE_TAG_LIST
Definition: Bottle.h:28
An interface for reading from a network connection.
virtual bool expectBlock(char *data, size_t len)=0
Read a block of data from the network connection.
virtual bool isBareMode() const =0
Check if the connection is bare mode.
virtual std::int32_t expectInt32()=0
Read a 32-bit integer from the network connection.
virtual bool convertTextMode()=0
Reads in a standard description in text mode, and converts it to a standard description in binary.
virtual bool isError() const =0
An interface for writing to a network connection.
virtual bool isError() const =0
virtual bool isBareMode() const =0
Check if the connection is bare mode.
virtual void appendExternalBlock(const char *data, size_t len)=0
Send a block of data to the network connection, without making a copy.
virtual bool convertTextMode()=0
Converts a standard description in binary into a textual description, if the connection is in text-mo...
virtual void appendInt32(std::int32_t data)=0
Send a representation of a 32-bit integer to the network connection.
static Type byName(const char *name)
Definition: Type.cpp:171
Type & addProperty(const char *key, const Value &val)
Definition: Type.cpp:134
A single value (typically within a Bottle).
Definition: Value.h:45
A "tamed" Portable, that promises to serialize itself in an IDL-friendly way.
Definition: WirePortable.h:23
virtual bool read(yarp::os::idl::WireReader &reader)
virtual bool write(const yarp::os::idl::WireWriter &writer) const
IDL-friendly connection reader.
Definition: WireReader.h:30
bool readBottle(yarp::os::ConnectionReader &connection) override
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
std::vector< yarp::rosmsg::geometry_msgs::Transform > transforms
yarp::os::idl::BareStyle< yarp::rosmsg::sensor_msgs::MultiDOFJointState > rosStyle
std::vector< yarp::rosmsg::geometry_msgs::Twist > twist
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
yarp::os::idl::BottleStyle< yarp::rosmsg::sensor_msgs::MultiDOFJointState > bottleStyle
std::vector< yarp::rosmsg::geometry_msgs::Wrench > wrench
bool readBare(yarp::os::ConnectionReader &connection) override
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
bool writeBare(yarp::os::ConnectionWriter &connection) const override
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: Header.h:159
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: Header.h:112
The main, catch-all namespace for YARP.
Definition: dirs.h:16