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