YARP
Yet Another Robot Platform
MultiDOFJointTrajectoryPoint.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/MultiDOFJointTrajectoryPoint" msg definition:
12 // # Each multi-dof joint can specify a transform (up to 6 DOF)
13 // geometry_msgs/Transform[] transforms
14 //
15 // # There can be a velocity specified for the origin of the joint
16 // geometry_msgs/Twist[] velocities
17 //
18 // # There can be an acceleration specified for the origin of the joint
19 // geometry_msgs/Twist[] accelerations
20 //
21 // duration time_from_start
22 // Instances of this class can be read and written with YARP ports,
23 // using a ROS-compatible format.
24 
25 #ifndef YARP_ROSMSG_trajectory_msgs_MultiDOFJointTrajectoryPoint_h
26 #define YARP_ROSMSG_trajectory_msgs_MultiDOFJointTrajectoryPoint_h
27 
28 #include <yarp/os/Wire.h>
29 #include <yarp/os/Type.h>
30 #include <yarp/os/idl/WireTypes.h>
31 #include <string>
32 #include <vector>
36 
37 namespace yarp {
38 namespace rosmsg {
39 namespace trajectory_msgs {
40 
42 {
43 public:
44  std::vector<yarp::rosmsg::geometry_msgs::Transform> transforms;
45  std::vector<yarp::rosmsg::geometry_msgs::Twist> velocities;
46  std::vector<yarp::rosmsg::geometry_msgs::Twist> accelerations;
48 
50  transforms(),
51  velocities(),
52  accelerations(),
54  {
55  }
56 
57  void clear()
58  {
59  // *** transforms ***
60  transforms.clear();
61 
62  // *** velocities ***
63  velocities.clear();
64 
65  // *** accelerations ***
66  accelerations.clear();
67 
68  // *** time_from_start ***
70  }
71 
72  bool readBare(yarp::os::ConnectionReader& connection) override
73  {
74  // *** transforms ***
75  int len = connection.expectInt32();
76  transforms.resize(len);
77  for (int i=0; i<len; i++) {
78  if (!transforms[i].read(connection)) {
79  return false;
80  }
81  }
82 
83  // *** velocities ***
84  len = connection.expectInt32();
85  velocities.resize(len);
86  for (int i=0; i<len; i++) {
87  if (!velocities[i].read(connection)) {
88  return false;
89  }
90  }
91 
92  // *** accelerations ***
93  len = connection.expectInt32();
94  accelerations.resize(len);
95  for (int i=0; i<len; i++) {
96  if (!accelerations[i].read(connection)) {
97  return false;
98  }
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(4)) {
114  return false;
115  }
116 
117  // *** transforms ***
118  if (connection.expectInt32() != BOTTLE_TAG_LIST) {
119  return false;
120  }
121  int len = connection.expectInt32();
122  transforms.resize(len);
123  for (int i=0; i<len; i++) {
124  if (!transforms[i].read(connection)) {
125  return false;
126  }
127  }
128 
129  // *** velocities ***
130  if (connection.expectInt32() != BOTTLE_TAG_LIST) {
131  return false;
132  }
133  len = connection.expectInt32();
134  velocities.resize(len);
135  for (int i=0; i<len; i++) {
136  if (!velocities[i].read(connection)) {
137  return false;
138  }
139  }
140 
141  // *** accelerations ***
142  if (connection.expectInt32() != BOTTLE_TAG_LIST) {
143  return false;
144  }
145  len = connection.expectInt32();
146  accelerations.resize(len);
147  for (int i=0; i<len; i++) {
148  if (!accelerations[i].read(connection)) {
149  return false;
150  }
151  }
152 
153  // *** time_from_start ***
154  if (!time_from_start.read(connection)) {
155  return false;
156  }
157 
158  return !connection.isError();
159  }
160 
162  bool read(yarp::os::ConnectionReader& connection) override
163  {
164  return (connection.isBareMode() ? readBare(connection)
165  : readBottle(connection));
166  }
167 
168  bool writeBare(yarp::os::ConnectionWriter& connection) const override
169  {
170  // *** transforms ***
171  connection.appendInt32(transforms.size());
172  for (size_t i=0; i<transforms.size(); i++) {
173  if (!transforms[i].write(connection)) {
174  return false;
175  }
176  }
177 
178  // *** velocities ***
179  connection.appendInt32(velocities.size());
180  for (size_t i=0; i<velocities.size(); i++) {
181  if (!velocities[i].write(connection)) {
182  return false;
183  }
184  }
185 
186  // *** accelerations ***
187  connection.appendInt32(accelerations.size());
188  for (size_t i=0; i<accelerations.size(); i++) {
189  if (!accelerations[i].write(connection)) {
190  return false;
191  }
192  }
193 
194  // *** time_from_start ***
195  if (!time_from_start.write(connection)) {
196  return false;
197  }
198 
199  return !connection.isError();
200  }
201 
202  bool writeBottle(yarp::os::ConnectionWriter& connection) const override
203  {
204  connection.appendInt32(BOTTLE_TAG_LIST);
205  connection.appendInt32(4);
206 
207  // *** transforms ***
208  connection.appendInt32(BOTTLE_TAG_LIST);
209  connection.appendInt32(transforms.size());
210  for (size_t i=0; i<transforms.size(); i++) {
211  if (!transforms[i].write(connection)) {
212  return false;
213  }
214  }
215 
216  // *** velocities ***
217  connection.appendInt32(BOTTLE_TAG_LIST);
218  connection.appendInt32(velocities.size());
219  for (size_t i=0; i<velocities.size(); i++) {
220  if (!velocities[i].write(connection)) {
221  return false;
222  }
223  }
224 
225  // *** accelerations ***
226  connection.appendInt32(BOTTLE_TAG_LIST);
227  connection.appendInt32(accelerations.size());
228  for (size_t i=0; i<accelerations.size(); i++) {
229  if (!accelerations[i].write(connection)) {
230  return false;
231  }
232  }
233 
234  // *** time_from_start ***
235  if (!time_from_start.write(connection)) {
236  return false;
237  }
238 
239  connection.convertTextMode();
240  return !connection.isError();
241  }
242 
244  bool write(yarp::os::ConnectionWriter& connection) const override
245  {
246  return (connection.isBareMode() ? writeBare(connection)
247  : writeBottle(connection));
248  }
249 
250  // This class will serialize ROS style or YARP style depending on protocol.
251  // If you need to force a serialization style, use one of these classes:
254 
255  // The name for this message, ROS will need this
256  static constexpr const char* typeName = "trajectory_msgs/MultiDOFJointTrajectoryPoint";
257 
258  // The checksum for this message, ROS will need this
259  static constexpr const char* typeChecksum = "3ebe08d1abd5b65862d50e09430db776";
260 
261  // The source text for this message, ROS will need this
262  static constexpr const char* typeText = "\
263 # Each multi-dof joint can specify a transform (up to 6 DOF)\n\
264 geometry_msgs/Transform[] transforms\n\
265 \n\
266 # There can be a velocity specified for the origin of the joint \n\
267 geometry_msgs/Twist[] velocities\n\
268 \n\
269 # There can be an acceleration specified for the origin of the joint \n\
270 geometry_msgs/Twist[] accelerations\n\
271 \n\
272 duration time_from_start\n\
273 \n\
274 ================================================================================\n\
275 MSG: geometry_msgs/Transform\n\
276 # This represents the transform between two coordinate frames in free space.\n\
277 \n\
278 Vector3 translation\n\
279 Quaternion rotation\n\
280 \n\
281 ================================================================================\n\
282 MSG: geometry_msgs/Vector3\n\
283 # This represents a vector in free space. \n\
284 # It is only meant to represent a direction. Therefore, it does not\n\
285 # make sense to apply a translation to it (e.g., when applying a \n\
286 # generic rigid transformation to a Vector3, tf2 will only apply the\n\
287 # rotation). If you want your data to be translatable too, use the\n\
288 # geometry_msgs/Point message instead.\n\
289 \n\
290 float64 x\n\
291 float64 y\n\
292 float64 z\n\
293 ================================================================================\n\
294 MSG: geometry_msgs/Quaternion\n\
295 # This represents an orientation in free space in quaternion form.\n\
296 \n\
297 float64 x\n\
298 float64 y\n\
299 float64 z\n\
300 float64 w\n\
301 \n\
302 ================================================================================\n\
303 MSG: geometry_msgs/Twist\n\
304 # This expresses velocity in free space broken into its linear and angular parts.\n\
305 Vector3 linear\n\
306 Vector3 angular\n\
307 ";
308 
309  yarp::os::Type getType() const override
310  {
312  typ.addProperty("md5sum", yarp::os::Value(typeChecksum));
313  typ.addProperty("message_definition", yarp::os::Value(typeText));
314  return typ;
315  }
316 };
317 
318 } // namespace trajectory_msgs
319 } // namespace rosmsg
320 } // namespace yarp
321 
322 #endif // YARP_ROSMSG_trajectory_msgs_MultiDOFJointTrajectoryPoint_h
yarp::rosmsg::trajectory_msgs::MultiDOFJointTrajectoryPoint::typeText
static constexpr const char * typeText
Definition: MultiDOFJointTrajectoryPoint.h:262
WireTypes.h
BOTTLE_TAG_LIST
#define BOTTLE_TAG_LIST
Definition: Bottle.h:30
TickDuration.h
yarp::rosmsg::trajectory_msgs::MultiDOFJointTrajectoryPoint::writeBottle
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
Definition: MultiDOFJointTrajectoryPoint.h:202
yarp::rosmsg::trajectory_msgs::MultiDOFJointTrajectoryPoint::readBottle
bool readBottle(yarp::os::ConnectionReader &connection) override
Definition: MultiDOFJointTrajectoryPoint.h:109
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::rosmsg::trajectory_msgs::MultiDOFJointTrajectoryPoint::writeBare
bool writeBare(yarp::os::ConnectionWriter &connection) const override
Definition: MultiDOFJointTrajectoryPoint.h:168
yarp::rosmsg::trajectory_msgs::MultiDOFJointTrajectoryPoint::write
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: MultiDOFJointTrajectoryPoint.h:244
yarp::os::ConnectionReader::isBareMode
virtual bool isBareMode() const =0
Check if the connection is bare mode.
Wire.h
yarp::rosmsg::trajectory_msgs::MultiDOFJointTrajectoryPoint
Definition: MultiDOFJointTrajectoryPoint.h:42
yarp::rosmsg::trajectory_msgs::MultiDOFJointTrajectoryPoint::typeChecksum
static constexpr const char * typeChecksum
Definition: MultiDOFJointTrajectoryPoint.h:259
Transform.h
yarp::rosmsg::trajectory_msgs::MultiDOFJointTrajectoryPoint::time_from_start
yarp::rosmsg::TickDuration time_from_start
Definition: MultiDOFJointTrajectoryPoint.h:47
yarp::rosmsg::TickDuration
Definition: TickDuration.h:30
yarp::rosmsg::trajectory_msgs::MultiDOFJointTrajectoryPoint::MultiDOFJointTrajectoryPoint
MultiDOFJointTrajectoryPoint()
Definition: MultiDOFJointTrajectoryPoint.h:49
yarp::os::ConnectionWriter::isError
virtual bool isError() const =0
yarp::rosmsg::trajectory_msgs::MultiDOFJointTrajectoryPoint::bottleStyle
yarp::os::idl::BottleStyle< yarp::rosmsg::trajectory_msgs::MultiDOFJointTrajectoryPoint > bottleStyle
Definition: MultiDOFJointTrajectoryPoint.h:253
yarp::os::Type::byName
static Type byName(const char *name)
Definition: Type.cpp:174
yarp::rosmsg::trajectory_msgs::MultiDOFJointTrajectoryPoint::velocities
std::vector< yarp::rosmsg::geometry_msgs::Twist > velocities
Definition: MultiDOFJointTrajectoryPoint.h:45
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::trajectory_msgs::MultiDOFJointTrajectoryPoint::typeName
static constexpr const char * typeName
Definition: MultiDOFJointTrajectoryPoint.h:256
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::MultiDOFJointTrajectoryPoint::clear
void clear()
Definition: MultiDOFJointTrajectoryPoint.h:57
yarp::rosmsg::trajectory_msgs::MultiDOFJointTrajectoryPoint::read
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: MultiDOFJointTrajectoryPoint.h:162
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.
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::trajectory_msgs::MultiDOFJointTrajectoryPoint::readBare
bool readBare(yarp::os::ConnectionReader &connection) override
Definition: MultiDOFJointTrajectoryPoint.h:72
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::rosmsg::trajectory_msgs::MultiDOFJointTrajectoryPoint::getType
yarp::os::Type getType() const override
Definition: MultiDOFJointTrajectoryPoint.h:309
yarp::rosmsg::TickDuration::clear
void clear()
Definition: TickDuration.h:78
yarp
The main, catch-all namespace for YARP.
Definition: environment.h:18
yarp::rosmsg::trajectory_msgs::MultiDOFJointTrajectoryPoint::accelerations
std::vector< yarp::rosmsg::geometry_msgs::Twist > accelerations
Definition: MultiDOFJointTrajectoryPoint.h:46
yarp::rosmsg::trajectory_msgs::MultiDOFJointTrajectoryPoint::rosStyle
yarp::os::idl::BareStyle< yarp::rosmsg::trajectory_msgs::MultiDOFJointTrajectoryPoint > rosStyle
Definition: MultiDOFJointTrajectoryPoint.h:252
trajectory_msgs
Definition: JointTrajectory.h:22
yarp::os::Value
A single value (typically within a Bottle).
Definition: Value.h:47
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::MultiDOFJointTrajectoryPoint::transforms
std::vector< yarp::rosmsg::geometry_msgs::Transform > transforms
Definition: MultiDOFJointTrajectoryPoint.h:44
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