36#ifndef YARP_ROSMSG_sensor_msgs_Imu_h
37#define YARP_ROSMSG_sensor_msgs_Imu_h
174 for (
int i=0; i<len; i++) {
189 for (
int i=0; i<len; i++) {
204 for (
int i=0; i<len; i++) {
321 static constexpr const char*
typeName =
"sensor_msgs/Imu";
324 static constexpr const char*
typeChecksum =
"6a62c6daae103f4ff57a132d6f95cec2";
328# This is a message to hold data from an IMU (Inertial Measurement Unit)\n\
330# Accelerations should be in m/s^2 (not in g's), and rotational velocity should be in rad/sec\n\
332# If the covariance of the measurement is known, it should be filled in (if all you know is the \n\
333# variance of each measurement, e.g. from the datasheet, just put those along the diagonal)\n\
334# A covariance matrix of all zeros will be interpreted as \"covariance unknown\", and to use the\n\
335# data a covariance will have to be assumed or gotten from some other source\n\
337# If you have no estimate for one of the data elements (e.g. your IMU doesn't produce an orientation \n\
338# estimate), please set element 0 of the associated covariance matrix to -1\n\
339# If you are interpreting this message, please check for a value of -1 in the first element of each \n\
340# covariance matrix, and disregard the associated estimate.\n\
344geometry_msgs/Quaternion orientation\n\
345float64[9] orientation_covariance # Row major about x, y, z axes\n\
347geometry_msgs/Vector3 angular_velocity\n\
348float64[9] angular_velocity_covariance # Row major about x, y, z axes\n\
350geometry_msgs/Vector3 linear_acceleration\n\
351float64[9] linear_acceleration_covariance # Row major x, y z \n\
353================================================================================\n\
354MSG: std_msgs/Header\n\
355# Standard metadata for higher-level stamped data types.\n\
356# This is generally used to communicate timestamped data \n\
357# in a particular coordinate frame.\n\
359# sequence ID: consecutively increasing ID \n\
361#Two-integer timestamp that is expressed as:\n\
362# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
363# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
364# time-handling sugar is provided by the client library\n\
366#Frame this data is associated with\n\
371================================================================================\n\
372MSG: geometry_msgs/Quaternion\n\
373# This represents an orientation in free space in quaternion form.\n\
380================================================================================\n\
381MSG: geometry_msgs/Vector3\n\
382# This represents a vector in free space. \n\
383# It is only meant to represent a direction. Therefore, it does not\n\
384# make sense to apply a translation to it (e.g., when applying a \n\
385# generic rigid transformation to a Vector3, tf2 will only apply the\n\
386# rotation). If you want your data to be translatable too, use the\n\
387# geometry_msgs/Point message instead.\n\
#define BOTTLE_TAG_FLOAT64
An interface for reading from a network connection.
virtual bool expectBlock(char *data, size_t len)=0
Read a block of data from the 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
virtual yarp::conf::float64_t expectFloat64()=0
Read a 64-bit floating point number from the network connection.
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 void appendExternalBlock(const char *data, size_t len)=0
Send a block of data to the network connection, without making a copy.
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.
virtual void appendFloat64(yarp::conf::float64_t data)=0
Send a representation of a 64-bit floating point number to the network connection.
static Type byName(const char *name)
Type & addProperty(const char *key, const Value &val)
A single value (typically within a Bottle).
A "tamed" Portable, that promises to serialize itself in an IDL-friendly way.
virtual bool read(yarp::os::idl::WireReader &reader)
virtual bool write(const yarp::os::idl::WireWriter &writer) const
IDL-friendly connection reader.
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 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.
yarp::os::Type getType() const override
static constexpr const char * typeChecksum
yarp::rosmsg::std_msgs::Header header
std::vector< yarp::conf::float64_t > orientation_covariance
yarp::rosmsg::geometry_msgs::Vector3 angular_velocity
std::vector< yarp::conf::float64_t > linear_acceleration_covariance
yarp::rosmsg::geometry_msgs::Vector3 linear_acceleration
bool writeBare(yarp::os::ConnectionWriter &connection) const override
yarp::rosmsg::geometry_msgs::Quaternion orientation
std::vector< yarp::conf::float64_t > angular_velocity_covariance
yarp::os::idl::BottleStyle< yarp::rosmsg::sensor_msgs::Imu > bottleStyle
static constexpr const char * typeText
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
yarp::os::idl::BareStyle< yarp::rosmsg::sensor_msgs::Imu > rosStyle
static constexpr const char * typeName
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 readBare(yarp::os::ConnectionReader &connection) override
bool readBottle(yarp::os::ConnectionReader &connection) override
The main, catch-all namespace for YARP.