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