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