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