YARP
Yet Another Robot Platform
JointTrajectoryPoint.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 "trajectory_msgs/JointTrajectoryPoint" msg definition:
9 // # Each trajectory point specifies either positions[, velocities[, accelerations]]
10 // # or positions[, effort] for the trajectory to be executed.
11 // # All specified values are in the same order as the joint names in JointTrajectory.msg
12 //
13 // float64[] positions
14 // float64[] velocities
15 // float64[] accelerations
16 // float64[] effort
17 // duration time_from_start
18 // Instances of this class can be read and written with YARP ports,
19 // using a ROS-compatible format.
20 
21 #ifndef YARP_ROSMSG_trajectory_msgs_JointTrajectoryPoint_h
22 #define YARP_ROSMSG_trajectory_msgs_JointTrajectoryPoint_h
23 
24 #include <yarp/os/Wire.h>
25 #include <yarp/os/Type.h>
26 #include <yarp/os/idl/WireTypes.h>
27 #include <string>
28 #include <vector>
30 
31 namespace yarp {
32 namespace rosmsg {
33 namespace trajectory_msgs {
34 
36 {
37 public:
38  std::vector<yarp::conf::float64_t> positions;
39  std::vector<yarp::conf::float64_t> velocities;
40  std::vector<yarp::conf::float64_t> accelerations;
41  std::vector<yarp::conf::float64_t> effort;
43 
45  positions(),
46  velocities(),
47  accelerations(),
48  effort(),
50  {
51  }
52 
53  void clear()
54  {
55  // *** positions ***
56  positions.clear();
57 
58  // *** velocities ***
59  velocities.clear();
60 
61  // *** accelerations ***
62  accelerations.clear();
63 
64  // *** effort ***
65  effort.clear();
66 
67  // *** time_from_start ***
69  }
70 
71  bool readBare(yarp::os::ConnectionReader& connection) override
72  {
73  // *** positions ***
74  int len = connection.expectInt32();
75  positions.resize(len);
76  if (len > 0 && !connection.expectBlock((char*)&positions[0], sizeof(yarp::conf::float64_t)*len)) {
77  return false;
78  }
79 
80  // *** velocities ***
81  len = connection.expectInt32();
82  velocities.resize(len);
83  if (len > 0 && !connection.expectBlock((char*)&velocities[0], sizeof(yarp::conf::float64_t)*len)) {
84  return false;
85  }
86 
87  // *** accelerations ***
88  len = connection.expectInt32();
89  accelerations.resize(len);
90  if (len > 0 && !connection.expectBlock((char*)&accelerations[0], sizeof(yarp::conf::float64_t)*len)) {
91  return false;
92  }
93 
94  // *** effort ***
95  len = connection.expectInt32();
96  effort.resize(len);
97  if (len > 0 && !connection.expectBlock((char*)&effort[0], sizeof(yarp::conf::float64_t)*len)) {
98  return false;
99  }
100 
101  // *** time_from_start ***
102  if (!time_from_start.read(connection)) {
103  return false;
104  }
105 
106  return !connection.isError();
107  }
108 
109  bool readBottle(yarp::os::ConnectionReader& connection) override
110  {
111  connection.convertTextMode();
112  yarp::os::idl::WireReader reader(connection);
113  if (!reader.readListHeader(5)) {
114  return false;
115  }
116 
117  // *** positions ***
118  if (connection.expectInt32() != (BOTTLE_TAG_LIST|BOTTLE_TAG_FLOAT64)) {
119  return false;
120  }
121  int len = connection.expectInt32();
122  positions.resize(len);
123  for (int i=0; i<len; i++) {
124  positions[i] = (yarp::conf::float64_t)connection.expectFloat64();
125  }
126 
127  // *** velocities ***
128  if (connection.expectInt32() != (BOTTLE_TAG_LIST|BOTTLE_TAG_FLOAT64)) {
129  return false;
130  }
131  len = connection.expectInt32();
132  velocities.resize(len);
133  for (int i=0; i<len; i++) {
135  }
136 
137  // *** accelerations ***
138  if (connection.expectInt32() != (BOTTLE_TAG_LIST|BOTTLE_TAG_FLOAT64)) {
139  return false;
140  }
141  len = connection.expectInt32();
142  accelerations.resize(len);
143  for (int i=0; i<len; i++) {
145  }
146 
147  // *** effort ***
148  if (connection.expectInt32() != (BOTTLE_TAG_LIST|BOTTLE_TAG_FLOAT64)) {
149  return false;
150  }
151  len = connection.expectInt32();
152  effort.resize(len);
153  for (int i=0; i<len; i++) {
154  effort[i] = (yarp::conf::float64_t)connection.expectFloat64();
155  }
156 
157  // *** time_from_start ***
158  if (!time_from_start.read(connection)) {
159  return false;
160  }
161 
162  return !connection.isError();
163  }
164 
166  bool read(yarp::os::ConnectionReader& connection) override
167  {
168  return (connection.isBareMode() ? readBare(connection)
169  : readBottle(connection));
170  }
171 
172  bool writeBare(yarp::os::ConnectionWriter& connection) const override
173  {
174  // *** positions ***
175  connection.appendInt32(positions.size());
176  if (positions.size()>0) {
177  connection.appendExternalBlock((char*)&positions[0], sizeof(yarp::conf::float64_t)*positions.size());
178  }
179 
180  // *** velocities ***
181  connection.appendInt32(velocities.size());
182  if (velocities.size()>0) {
183  connection.appendExternalBlock((char*)&velocities[0], sizeof(yarp::conf::float64_t)*velocities.size());
184  }
185 
186  // *** accelerations ***
187  connection.appendInt32(accelerations.size());
188  if (accelerations.size()>0) {
189  connection.appendExternalBlock((char*)&accelerations[0], sizeof(yarp::conf::float64_t)*accelerations.size());
190  }
191 
192  // *** effort ***
193  connection.appendInt32(effort.size());
194  if (effort.size()>0) {
195  connection.appendExternalBlock((char*)&effort[0], sizeof(yarp::conf::float64_t)*effort.size());
196  }
197 
198  // *** time_from_start ***
199  if (!time_from_start.write(connection)) {
200  return false;
201  }
202 
203  return !connection.isError();
204  }
205 
206  bool writeBottle(yarp::os::ConnectionWriter& connection) const override
207  {
208  connection.appendInt32(BOTTLE_TAG_LIST);
209  connection.appendInt32(5);
210 
211  // *** positions ***
213  connection.appendInt32(positions.size());
214  for (size_t i=0; i<positions.size(); i++) {
215  connection.appendFloat64(positions[i]);
216  }
217 
218  // *** velocities ***
220  connection.appendInt32(velocities.size());
221  for (size_t i=0; i<velocities.size(); i++) {
222  connection.appendFloat64(velocities[i]);
223  }
224 
225  // *** accelerations ***
227  connection.appendInt32(accelerations.size());
228  for (size_t i=0; i<accelerations.size(); i++) {
229  connection.appendFloat64(accelerations[i]);
230  }
231 
232  // *** effort ***
234  connection.appendInt32(effort.size());
235  for (size_t i=0; i<effort.size(); i++) {
236  connection.appendFloat64(effort[i]);
237  }
238 
239  // *** time_from_start ***
240  if (!time_from_start.write(connection)) {
241  return false;
242  }
243 
244  connection.convertTextMode();
245  return !connection.isError();
246  }
247 
249  bool write(yarp::os::ConnectionWriter& connection) const override
250  {
251  return (connection.isBareMode() ? writeBare(connection)
252  : writeBottle(connection));
253  }
254 
255  // This class will serialize ROS style or YARP style depending on protocol.
256  // If you need to force a serialization style, use one of these classes:
259 
260  // The name for this message, ROS will need this
261  static constexpr const char* typeName = "trajectory_msgs/JointTrajectoryPoint";
262 
263  // The checksum for this message, ROS will need this
264  static constexpr const char* typeChecksum = "f3cd1e1c4d320c79d6985c904ae5dcd3";
265 
266  // The source text for this message, ROS will need this
267  static constexpr const char* typeText = "\
268 # Each trajectory point specifies either positions[, velocities[, accelerations]]\n\
269 # or positions[, effort] for the trajectory to be executed.\n\
270 # All specified values are in the same order as the joint names in JointTrajectory.msg\n\
271 \n\
272 float64[] positions\n\
273 float64[] velocities\n\
274 float64[] accelerations\n\
275 float64[] effort\n\
276 duration time_from_start\n\
277 ";
278 
279  yarp::os::Type getType() const override
280  {
282  typ.addProperty("md5sum", yarp::os::Value(typeChecksum));
283  typ.addProperty("message_definition", yarp::os::Value(typeText));
284  return typ;
285  }
286 };
287 
288 } // namespace trajectory_msgs
289 } // namespace rosmsg
290 } // namespace yarp
291 
292 #endif // YARP_ROSMSG_trajectory_msgs_JointTrajectoryPoint_h
#define BOTTLE_TAG_FLOAT64
Definition: Bottle.h:25
#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
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: TickDuration.h:148
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: TickDuration.h:113
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
bool writeBare(yarp::os::ConnectionWriter &connection) const override
yarp::os::idl::BottleStyle< yarp::rosmsg::trajectory_msgs::JointTrajectoryPoint > bottleStyle
bool readBare(yarp::os::ConnectionReader &connection) override
yarp::os::idl::BareStyle< yarp::rosmsg::trajectory_msgs::JointTrajectoryPoint > rosStyle
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
std::vector< yarp::conf::float64_t > positions
bool readBottle(yarp::os::ConnectionReader &connection) override
std::vector< yarp::conf::float64_t > accelerations
std::vector< yarp::conf::float64_t > velocities
double float64_t
Definition: numeric.h:77
The main, catch-all namespace for YARP.
Definition: dirs.h:16