YARP
Yet Another Robot Platform
PoseWithCovarianceStamped.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 "geometry_msgs/PoseWithCovarianceStamped" msg definition:
9 // # This expresses an estimated pose with a reference coordinate frame and timestamp
10 //
11 // Header header
12 // PoseWithCovariance pose
13 // Instances of this class can be read and written with YARP ports,
14 // using a ROS-compatible format.
15 
16 #ifndef YARP_ROSMSG_geometry_msgs_PoseWithCovarianceStamped_h
17 #define YARP_ROSMSG_geometry_msgs_PoseWithCovarianceStamped_h
18 
19 #include <yarp/os/Wire.h>
20 #include <yarp/os/Type.h>
22 #include <string>
23 #include <vector>
26 
27 namespace yarp {
28 namespace rosmsg {
29 namespace geometry_msgs {
30 
32 {
33 public:
36 
38  header(),
39  pose()
40  {
41  }
42 
43  void clear()
44  {
45  // *** header ***
46  header.clear();
47 
48  // *** pose ***
49  pose.clear();
50  }
51 
52  bool readBare(yarp::os::ConnectionReader& connection) override
53  {
54  // *** header ***
55  if (!header.read(connection)) {
56  return false;
57  }
58 
59  // *** pose ***
60  if (!pose.read(connection)) {
61  return false;
62  }
63 
64  return !connection.isError();
65  }
66 
67  bool readBottle(yarp::os::ConnectionReader& connection) override
68  {
69  connection.convertTextMode();
70  yarp::os::idl::WireReader reader(connection);
71  if (!reader.readListHeader(2)) {
72  return false;
73  }
74 
75  // *** header ***
76  if (!header.read(connection)) {
77  return false;
78  }
79 
80  // *** pose ***
81  if (!pose.read(connection)) {
82  return false;
83  }
84 
85  return !connection.isError();
86  }
87 
89  bool read(yarp::os::ConnectionReader& connection) override
90  {
91  return (connection.isBareMode() ? readBare(connection)
92  : readBottle(connection));
93  }
94 
95  bool writeBare(yarp::os::ConnectionWriter& connection) const override
96  {
97  // *** header ***
98  if (!header.write(connection)) {
99  return false;
100  }
101 
102  // *** pose ***
103  if (!pose.write(connection)) {
104  return false;
105  }
106 
107  return !connection.isError();
108  }
109 
110  bool writeBottle(yarp::os::ConnectionWriter& connection) const override
111  {
112  connection.appendInt32(BOTTLE_TAG_LIST);
113  connection.appendInt32(2);
114 
115  // *** header ***
116  if (!header.write(connection)) {
117  return false;
118  }
119 
120  // *** pose ***
121  if (!pose.write(connection)) {
122  return false;
123  }
124 
125  connection.convertTextMode();
126  return !connection.isError();
127  }
128 
130  bool write(yarp::os::ConnectionWriter& connection) const override
131  {
132  return (connection.isBareMode() ? writeBare(connection)
133  : writeBottle(connection));
134  }
135 
136  // This class will serialize ROS style or YARP style depending on protocol.
137  // If you need to force a serialization style, use one of these classes:
140 
141  // The name for this message, ROS will need this
142  static constexpr const char* typeName = "geometry_msgs/PoseWithCovarianceStamped";
143 
144  // The checksum for this message, ROS will need this
145  static constexpr const char* typeChecksum = "953b798c0f514ff060a53a3498ce6246";
146 
147  // The source text for this message, ROS will need this
148  static constexpr const char* typeText = "\
149 # This expresses an estimated pose with a reference coordinate frame and timestamp\n\
150 \n\
151 Header header\n\
152 PoseWithCovariance pose\n\
153 \n\
154 ================================================================================\n\
155 MSG: std_msgs/Header\n\
156 # Standard metadata for higher-level stamped data types.\n\
157 # This is generally used to communicate timestamped data \n\
158 # in a particular coordinate frame.\n\
159 # \n\
160 # sequence ID: consecutively increasing ID \n\
161 uint32 seq\n\
162 #Two-integer timestamp that is expressed as:\n\
163 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
164 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
165 # time-handling sugar is provided by the client library\n\
166 time stamp\n\
167 #Frame this data is associated with\n\
168 # 0: no frame\n\
169 # 1: global frame\n\
170 string frame_id\n\
171 \n\
172 ================================================================================\n\
173 MSG: geometry_msgs/PoseWithCovariance\n\
174 # This represents a pose in free space with uncertainty.\n\
175 \n\
176 Pose pose\n\
177 \n\
178 # Row-major representation of the 6x6 covariance matrix\n\
179 # The orientation parameters use a fixed-axis representation.\n\
180 # In order, the parameters are:\n\
181 # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n\
182 float64[36] covariance\n\
183 \n\
184 ================================================================================\n\
185 MSG: geometry_msgs/Pose\n\
186 # A representation of pose in free space, composed of position and orientation. \n\
187 Point position\n\
188 Quaternion orientation\n\
189 \n\
190 ================================================================================\n\
191 MSG: geometry_msgs/Point\n\
192 # This contains the position of a point in free space\n\
193 float64 x\n\
194 float64 y\n\
195 float64 z\n\
196 \n\
197 ================================================================================\n\
198 MSG: geometry_msgs/Quaternion\n\
199 # This represents an orientation in free space in quaternion form.\n\
200 \n\
201 float64 x\n\
202 float64 y\n\
203 float64 z\n\
204 float64 w\n\
205 ";
206 
207  yarp::os::Type getType() const override
208  {
210  typ.addProperty("md5sum", yarp::os::Value(typeChecksum));
211  typ.addProperty("message_definition", yarp::os::Value(typeText));
212  return typ;
213  }
214 };
215 
216 } // namespace geometry_msgs
217 } // namespace rosmsg
218 } // namespace yarp
219 
220 #endif // YARP_ROSMSG_geometry_msgs_PoseWithCovarianceStamped_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 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.
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
bool readBare(yarp::os::ConnectionReader &connection) override
bool readBottle(yarp::os::ConnectionReader &connection) override
bool writeBare(yarp::os::ConnectionWriter &connection) const override
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
yarp::os::idl::BottleStyle< yarp::rosmsg::geometry_msgs::PoseWithCovarianceStamped > bottleStyle
yarp::os::idl::BareStyle< yarp::rosmsg::geometry_msgs::PoseWithCovarianceStamped > rosStyle
yarp::rosmsg::geometry_msgs::PoseWithCovariance pose
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.
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: Header.h:159
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: Header.h:112
The main, catch-all namespace for YARP.
Definition: dirs.h:16