|
YARP
Yet Another Robot Platform
|
|
Go to the documentation of this file.
22 #ifndef YARP_ROSMSG_nav_msgs_Odometry_h
23 #define YARP_ROSMSG_nav_msgs_Odometry_h
200 static constexpr
const char*
typeName =
"nav_msgs/Odometry";
203 static constexpr
const char*
typeChecksum =
"cd5e73d190d741a2f92e81eda573aca7";
207 # This represents an estimate of a position and velocity in free space. \n\
208 # The pose in this message should be specified in the coordinate frame given by header.frame_id.\n\
209 # The twist in this message should be specified in the coordinate frame given by the child_frame_id\n\
211 string child_frame_id\n\
212 geometry_msgs/PoseWithCovariance pose\n\
213 geometry_msgs/TwistWithCovariance twist\n\
215 ================================================================================\n\
216 MSG: std_msgs/Header\n\
217 # Standard metadata for higher-level stamped data types.\n\
218 # This is generally used to communicate timestamped data \n\
219 # in a particular coordinate frame.\n\
221 # sequence ID: consecutively increasing ID \n\
223 #Two-integer timestamp that is expressed as:\n\
224 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
225 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
226 # time-handling sugar is provided by the client library\n\
228 #Frame this data is associated with\n\
233 ================================================================================\n\
234 MSG: geometry_msgs/PoseWithCovariance\n\
235 # This represents a pose in free space with uncertainty.\n\
239 # Row-major representation of the 6x6 covariance matrix\n\
240 # The orientation parameters use a fixed-axis representation.\n\
241 # In order, the parameters are:\n\
242 # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n\
243 float64[36] covariance\n\
245 ================================================================================\n\
246 MSG: geometry_msgs/Pose\n\
247 # A representation of pose in free space, composed of position and orientation. \n\
249 Quaternion orientation\n\
251 ================================================================================\n\
252 MSG: geometry_msgs/Point\n\
253 # This contains the position of a point in free space\n\
258 ================================================================================\n\
259 MSG: geometry_msgs/Quaternion\n\
260 # This represents an orientation in free space in quaternion form.\n\
267 ================================================================================\n\
268 MSG: geometry_msgs/TwistWithCovariance\n\
269 # This expresses velocity in free space with uncertainty.\n\
273 # Row-major representation of the 6x6 covariance matrix\n\
274 # The orientation parameters use a fixed-axis representation.\n\
275 # In order, the parameters are:\n\
276 # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n\
277 float64[36] covariance\n\
279 ================================================================================\n\
280 MSG: geometry_msgs/Twist\n\
281 # This expresses velocity in free space broken into its linear and angular parts.\n\
285 ================================================================================\n\
286 MSG: geometry_msgs/Vector3\n\
287 # This represents a vector in free space. \n\
288 # It is only meant to represent a direction. Therefore, it does not\n\
289 # make sense to apply a translation to it (e.g., when applying a \n\
290 # generic rigid transformation to a Vector3, tf2 will only apply the\n\
291 # rotation). If you want your data to be translatable too, use the\n\
292 # geometry_msgs/Point message instead.\n\
312 #endif // YARP_ROSMSG_nav_msgs_Odometry_h
bool readString(std::string &str, bool *is_vocab=nullptr)
yarp::os::idl::BareStyle< yarp::rosmsg::nav_msgs::Odometry > rosStyle
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
virtual bool read(yarp::os::idl::WireReader &reader)
virtual bool isBareMode() const =0
Check if the connection is bare mode.
#define BOTTLE_TAG_STRING
yarp::os::Type getType() const override
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
virtual bool isError() const =0
static constexpr const char * typeText
static Type byName(const char *name)
virtual std::int32_t expectInt32()=0
Read a 32-bit integer from the network connection.
Type & addProperty(const char *key, const Value &val)
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
An interface for writing to a network connection.
yarp::os::idl::BottleStyle< yarp::rosmsg::nav_msgs::Odometry > bottleStyle
virtual bool isError() const =0
static constexpr const char * typeName
virtual bool convertTextMode()=0
Reads in a standard description in text mode, and converts it to a standard description in binary.
yarp::rosmsg::geometry_msgs::PoseWithCovariance pose
A "tamed" Portable, that promises to serialize itself in an IDL-friendly way.
std::string child_frame_id
virtual bool isBareMode() const =0
Check if the connection is bare mode.
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
yarp::rosmsg::geometry_msgs::TwistWithCovariance twist
bool readBottle(yarp::os::ConnectionReader &connection) override
bool writeBare(yarp::os::ConnectionWriter &connection) const override
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.
IDL-friendly connection reader.
An interface for reading from a network connection.
static constexpr const char * typeChecksum
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
The main, catch-all namespace for YARP.
yarp::rosmsg::std_msgs::Header header
bool readBare(yarp::os::ConnectionReader &connection) override
virtual void appendExternalBlock(const char *data, size_t len)=0
Send a block of data to the network connection, without making a copy.
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
virtual bool expectBlock(char *data, size_t len)=0
Read a block of data from the network connection.
A single value (typically within a Bottle).
virtual bool write(const yarp::os::idl::WireWriter &writer) const