YARP
Yet Another Robot Platform
JointState.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/JointState" msg definition:
9 // # This is a message that holds data to describe the state of a set of torque controlled joints.
10 // #
11 // # The state of each joint (revolute or prismatic) is defined by:
12 // # * the position of the joint (rad or m),
13 // # * the velocity of the joint (rad/s or m/s) and
14 // # * the effort that is applied in the joint (Nm or N).
15 // #
16 // # Each joint is uniquely identified by its name
17 // # The header specifies the time at which the joint states were recorded. All the joint states
18 // # in one message have to be recorded at the same time.
19 // #
20 // # This message consists of a multiple arrays, one for each part of the joint state.
21 // # The goal is to make each of the fields optional. When e.g. your joints have no
22 // # effort associated with them, you can leave the effort array empty.
23 // #
24 // # All arrays in this message should have the same size, or be empty.
25 // # This is the only way to uniquely associate the joint name with the correct
26 // # states.
27 //
28 //
29 // Header header
30 //
31 // string[] name
32 // float64[] position
33 // float64[] velocity
34 // float64[] effort
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_JointState_h
39 #define YARP_ROSMSG_sensor_msgs_JointState_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>
47 
48 namespace yarp {
49 namespace rosmsg {
50 namespace sensor_msgs {
51 
53 {
54 public:
56  std::vector<std::string> name;
57  std::vector<yarp::conf::float64_t> position;
58  std::vector<yarp::conf::float64_t> velocity;
59  std::vector<yarp::conf::float64_t> effort;
60 
62  header(),
63  name(),
64  position(),
65  velocity(),
66  effort()
67  {
68  }
69 
70  void clear()
71  {
72  // *** header ***
73  header.clear();
74 
75  // *** name ***
76  name.clear();
77 
78  // *** position ***
79  position.clear();
80 
81  // *** velocity ***
82  velocity.clear();
83 
84  // *** effort ***
85  effort.clear();
86  }
87 
88  bool readBare(yarp::os::ConnectionReader& connection) override
89  {
90  // *** header ***
91  if (!header.read(connection)) {
92  return false;
93  }
94 
95  // *** name ***
96  int len = connection.expectInt32();
97  name.resize(len);
98  for (int i=0; i<len; i++) {
99  int len2 = connection.expectInt32();
100  name[i].resize(len2);
101  if (!connection.expectBlock((char*)name[i].c_str(), len2)) {
102  return false;
103  }
104  }
105 
106  // *** position ***
107  len = connection.expectInt32();
108  position.resize(len);
109  if (len > 0 && !connection.expectBlock((char*)&position[0], sizeof(yarp::conf::float64_t)*len)) {
110  return false;
111  }
112 
113  // *** velocity ***
114  len = connection.expectInt32();
115  velocity.resize(len);
116  if (len > 0 && !connection.expectBlock((char*)&velocity[0], sizeof(yarp::conf::float64_t)*len)) {
117  return false;
118  }
119 
120  // *** effort ***
121  len = connection.expectInt32();
122  effort.resize(len);
123  if (len > 0 && !connection.expectBlock((char*)&effort[0], sizeof(yarp::conf::float64_t)*len)) {
124  return false;
125  }
126 
127  return !connection.isError();
128  }
129 
130  bool readBottle(yarp::os::ConnectionReader& connection) override
131  {
132  connection.convertTextMode();
133  yarp::os::idl::WireReader reader(connection);
134  if (!reader.readListHeader(5)) {
135  return false;
136  }
137 
138  // *** header ***
139  if (!header.read(connection)) {
140  return false;
141  }
142 
143  // *** name ***
144  if (connection.expectInt32() != (BOTTLE_TAG_LIST|BOTTLE_TAG_STRING)) {
145  return false;
146  }
147  int len = connection.expectInt32();
148  name.resize(len);
149  for (int i=0; i<len; i++) {
150  int len2 = connection.expectInt32();
151  name[i].resize(len2);
152  if (!connection.expectBlock((char*)name[i].c_str(), len2)) {
153  return false;
154  }
155  }
156 
157  // *** position ***
158  if (connection.expectInt32() != (BOTTLE_TAG_LIST|BOTTLE_TAG_FLOAT64)) {
159  return false;
160  }
161  len = connection.expectInt32();
162  position.resize(len);
163  for (int i=0; i<len; i++) {
164  position[i] = (yarp::conf::float64_t)connection.expectFloat64();
165  }
166 
167  // *** velocity ***
168  if (connection.expectInt32() != (BOTTLE_TAG_LIST|BOTTLE_TAG_FLOAT64)) {
169  return false;
170  }
171  len = connection.expectInt32();
172  velocity.resize(len);
173  for (int i=0; i<len; i++) {
174  velocity[i] = (yarp::conf::float64_t)connection.expectFloat64();
175  }
176 
177  // *** effort ***
178  if (connection.expectInt32() != (BOTTLE_TAG_LIST|BOTTLE_TAG_FLOAT64)) {
179  return false;
180  }
181  len = connection.expectInt32();
182  effort.resize(len);
183  for (int i=0; i<len; i++) {
184  effort[i] = (yarp::conf::float64_t)connection.expectFloat64();
185  }
186 
187  return !connection.isError();
188  }
189 
191  bool read(yarp::os::ConnectionReader& connection) override
192  {
193  return (connection.isBareMode() ? readBare(connection)
194  : readBottle(connection));
195  }
196 
197  bool writeBare(yarp::os::ConnectionWriter& connection) const override
198  {
199  // *** header ***
200  if (!header.write(connection)) {
201  return false;
202  }
203 
204  // *** name ***
205  connection.appendInt32(name.size());
206  for (size_t i=0; i<name.size(); i++) {
207  connection.appendInt32(name[i].length());
208  connection.appendExternalBlock((char*)name[i].c_str(), name[i].length());
209  }
210 
211  // *** position ***
212  connection.appendInt32(position.size());
213  if (position.size()>0) {
214  connection.appendExternalBlock((char*)&position[0], sizeof(yarp::conf::float64_t)*position.size());
215  }
216 
217  // *** velocity ***
218  connection.appendInt32(velocity.size());
219  if (velocity.size()>0) {
220  connection.appendExternalBlock((char*)&velocity[0], sizeof(yarp::conf::float64_t)*velocity.size());
221  }
222 
223  // *** effort ***
224  connection.appendInt32(effort.size());
225  if (effort.size()>0) {
226  connection.appendExternalBlock((char*)&effort[0], sizeof(yarp::conf::float64_t)*effort.size());
227  }
228 
229  return !connection.isError();
230  }
231 
232  bool writeBottle(yarp::os::ConnectionWriter& connection) const override
233  {
234  connection.appendInt32(BOTTLE_TAG_LIST);
235  connection.appendInt32(5);
236 
237  // *** header ***
238  if (!header.write(connection)) {
239  return false;
240  }
241 
242  // *** name ***
244  connection.appendInt32(name.size());
245  for (size_t i=0; i<name.size(); i++) {
246  connection.appendInt32(name[i].length());
247  connection.appendExternalBlock((char*)name[i].c_str(), name[i].length());
248  }
249 
250  // *** position ***
252  connection.appendInt32(position.size());
253  for (size_t i=0; i<position.size(); i++) {
254  connection.appendFloat64(position[i]);
255  }
256 
257  // *** velocity ***
259  connection.appendInt32(velocity.size());
260  for (size_t i=0; i<velocity.size(); i++) {
261  connection.appendFloat64(velocity[i]);
262  }
263 
264  // *** effort ***
266  connection.appendInt32(effort.size());
267  for (size_t i=0; i<effort.size(); i++) {
268  connection.appendFloat64(effort[i]);
269  }
270 
271  connection.convertTextMode();
272  return !connection.isError();
273  }
274 
276  bool write(yarp::os::ConnectionWriter& connection) const override
277  {
278  return (connection.isBareMode() ? writeBare(connection)
279  : writeBottle(connection));
280  }
281 
282  // This class will serialize ROS style or YARP style depending on protocol.
283  // If you need to force a serialization style, use one of these classes:
286 
287  // The name for this message, ROS will need this
288  static constexpr const char* typeName = "sensor_msgs/JointState";
289 
290  // The checksum for this message, ROS will need this
291  static constexpr const char* typeChecksum = "3066dcd76a6cfaef579bd0f34173e9fd";
292 
293  // The source text for this message, ROS will need this
294  static constexpr const char* typeText = "\
295 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
296 #\n\
297 # The state of each joint (revolute or prismatic) is defined by:\n\
298 # * the position of the joint (rad or m),\n\
299 # * the velocity of the joint (rad/s or m/s) and \n\
300 # * the effort that is applied in the joint (Nm or N).\n\
301 #\n\
302 # Each joint is uniquely identified by its name\n\
303 # The header specifies the time at which the joint states were recorded. All the joint states\n\
304 # in one message have to be recorded at the same time.\n\
305 #\n\
306 # This message consists of a multiple arrays, one for each part of the joint state. \n\
307 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
308 # effort associated with them, you can leave the effort array empty. \n\
309 #\n\
310 # All arrays in this message should have the same size, or be empty.\n\
311 # This is the only way to uniquely associate the joint name with the correct\n\
312 # states.\n\
313 \n\
314 \n\
315 Header header\n\
316 \n\
317 string[] name\n\
318 float64[] position\n\
319 float64[] velocity\n\
320 float64[] effort\n\
321 \n\
322 ================================================================================\n\
323 MSG: std_msgs/Header\n\
324 # Standard metadata for higher-level stamped data types.\n\
325 # This is generally used to communicate timestamped data \n\
326 # in a particular coordinate frame.\n\
327 # \n\
328 # sequence ID: consecutively increasing ID \n\
329 uint32 seq\n\
330 #Two-integer timestamp that is expressed as:\n\
331 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
332 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
333 # time-handling sugar is provided by the client library\n\
334 time stamp\n\
335 #Frame this data is associated with\n\
336 # 0: no frame\n\
337 # 1: global frame\n\
338 string frame_id\n\
339 ";
340 
341  yarp::os::Type getType() const override
342  {
344  typ.addProperty("md5sum", yarp::os::Value(typeChecksum));
345  typ.addProperty("message_definition", yarp::os::Value(typeText));
346  return typ;
347  }
348 };
349 
350 } // namespace sensor_msgs
351 } // namespace rosmsg
352 } // namespace yarp
353 
354 #endif // YARP_ROSMSG_sensor_msgs_JointState_h
#define BOTTLE_TAG_FLOAT64
Definition: Bottle.h:25
#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
virtual yarp::conf::float64_t expectFloat64()=0
Read a 64-bit floating point number from the network connection.
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.
virtual void appendFloat64(yarp::conf::float64_t data)=0
Send a representation of a 64-bit floating point number 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
static constexpr const char * typeName
Definition: JointState.h:288
std::vector< std::string > name
Definition: JointState.h:56
static constexpr const char * typeText
Definition: JointState.h:294
bool writeBare(yarp::os::ConnectionWriter &connection) const override
Definition: JointState.h:197
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: JointState.h:191
static constexpr const char * typeChecksum
Definition: JointState.h:291
bool readBottle(yarp::os::ConnectionReader &connection) override
Definition: JointState.h:130
std::vector< yarp::conf::float64_t > position
Definition: JointState.h:57
std::vector< yarp::conf::float64_t > velocity
Definition: JointState.h:58
bool readBare(yarp::os::ConnectionReader &connection) override
Definition: JointState.h:88
yarp::os::idl::BareStyle< yarp::rosmsg::sensor_msgs::JointState > rosStyle
Definition: JointState.h:284
yarp::os::idl::BottleStyle< yarp::rosmsg::sensor_msgs::JointState > bottleStyle
Definition: JointState.h:285
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: JointState.h:276
std::vector< yarp::conf::float64_t > effort
Definition: JointState.h:59
yarp::os::Type getType() const override
Definition: JointState.h:341
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
Definition: JointState.h:232
yarp::rosmsg::std_msgs::Header header
Definition: JointState.h:55
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
double float64_t
Definition: numeric.h:77
The main, catch-all namespace for YARP.
Definition: dirs.h:16