|  | YARP Yet Another Robot Platform |  | 
 
 
 
Go to the documentation of this file.
   18 #ifndef YARP_ROSMSG_geometry_msgs_TwistWithCovarianceStamped_h 
   19 #define YARP_ROSMSG_geometry_msgs_TwistWithCovarianceStamped_h 
  144     static constexpr 
const char* 
typeName = 
"geometry_msgs/TwistWithCovarianceStamped";
 
  147     static constexpr 
const char* 
typeChecksum = 
"8927a1a12fb2607ceea095b2dc440a96";
 
  151 # This represents an estimated twist with reference coordinate frame and timestamp.\n\ 
  153 TwistWithCovariance twist\n\ 
  155 ================================================================================\n\ 
  156 MSG: std_msgs/Header\n\ 
  157 # Standard metadata for higher-level stamped data types.\n\ 
  158 # This is generally used to communicate timestamped data \n\ 
  159 # in a particular coordinate frame.\n\ 
  161 # sequence ID: consecutively increasing ID \n\ 
  163 #Two-integer timestamp that is expressed as:\n\ 
  164 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ 
  165 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ 
  166 # time-handling sugar is provided by the client library\n\ 
  168 #Frame this data is associated with\n\ 
  173 ================================================================================\n\ 
  174 MSG: geometry_msgs/TwistWithCovariance\n\ 
  175 # This expresses velocity in free space with uncertainty.\n\ 
  179 # Row-major representation of the 6x6 covariance matrix\n\ 
  180 # The orientation parameters use a fixed-axis representation.\n\ 
  181 # In order, the parameters are:\n\ 
  182 # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n\ 
  183 float64[36] covariance\n\ 
  185 ================================================================================\n\ 
  186 MSG: geometry_msgs/Twist\n\ 
  187 # This expresses velocity in free space broken into its linear and angular parts.\n\ 
  191 ================================================================================\n\ 
  192 MSG: geometry_msgs/Vector3\n\ 
  193 # This represents a vector in free space. \n\ 
  194 # It is only meant to represent a direction. Therefore, it does not\n\ 
  195 # make sense to apply a translation to it (e.g., when applying a \n\ 
  196 # generic rigid transformation to a Vector3, tf2 will only apply the\n\ 
  197 # rotation). If you want your data to be translatable too, use the\n\ 
  198 # geometry_msgs/Point message instead.\n\ 
  218 #endif // YARP_ROSMSG_geometry_msgs_TwistWithCovarianceStamped_h 
  
 
static constexpr const char * typeText
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
yarp::os::idl::BareStyle< yarp::rosmsg::geometry_msgs::TwistWithCovarianceStamped > rosStyle
virtual bool read(yarp::os::idl::WireReader &reader)
virtual bool isBareMode() const =0
Check if the connection is bare mode.
TwistWithCovarianceStamped()
yarp::rosmsg::geometry_msgs::TwistWithCovariance twist
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
static constexpr const char * typeName
virtual bool isError() const =0
yarp::os::Type getType() const override
bool writeBare(yarp::os::ConnectionWriter &connection) const override
static Type byName(const char *name)
static constexpr const char * typeChecksum
Type & addProperty(const char *key, const Value &val)
An interface for writing to a network connection.
virtual bool isError() const =0
bool readBottle(yarp::os::ConnectionReader &connection) override
virtual bool convertTextMode()=0
Reads in a standard description in text mode, and converts it to a standard description in binary.
A "tamed" Portable, that promises to serialize itself in an IDL-friendly way.
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.
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.
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
bool readBare(yarp::os::ConnectionReader &connection) override
The main, catch-all namespace for YARP.
yarp::os::idl::BottleStyle< yarp::rosmsg::geometry_msgs::TwistWithCovarianceStamped > bottleStyle
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
A single value (typically within a Bottle).
yarp::rosmsg::std_msgs::Header header
virtual bool write(const yarp::os::idl::WireWriter &writer) const