|
YARP
Yet Another Robot Platform
|
|
Go to the documentation of this file.
41 #ifndef YARP_ROSMSG_sensor_msgs_JointState_h
42 #define YARP_ROSMSG_sensor_msgs_JointState_h
59 std::vector<std::string>
name;
62 std::vector<yarp::conf::float64_t>
effort;
101 for (
int i=0; i<len; i++) {
103 name[i].resize(len2);
152 for (
int i=0; i<len; i++) {
154 name[i].resize(len2);
166 for (
int i=0; i<len; i++) {
176 for (
int i=0; i<len; i++) {
186 for (
int i=0; i<len; i++) {
209 for (
size_t i=0; i<
name.size(); i++) {
248 for (
size_t i=0; i<
name.size(); i++) {
256 for (
size_t i=0; i<
position.size(); i++) {
263 for (
size_t i=0; i<
velocity.size(); i++) {
270 for (
size_t i=0; i<
effort.size(); i++) {
291 static constexpr
const char*
typeName =
"sensor_msgs/JointState";
294 static constexpr
const char*
typeChecksum =
"3066dcd76a6cfaef579bd0f34173e9fd";
298 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
300 # The state of each joint (revolute or prismatic) is defined by:\n\
301 # * the position of the joint (rad or m),\n\
302 # * the velocity of the joint (rad/s or m/s) and \n\
303 # * the effort that is applied in the joint (Nm or N).\n\
305 # Each joint is uniquely identified by its name\n\
306 # The header specifies the time at which the joint states were recorded. All the joint states\n\
307 # in one message have to be recorded at the same time.\n\
309 # This message consists of a multiple arrays, one for each part of the joint state. \n\
310 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
311 # effort associated with them, you can leave the effort array empty. \n\
313 # All arrays in this message should have the same size, or be empty.\n\
314 # This is the only way to uniquely associate the joint name with the correct\n\
321 float64[] position\n\
322 float64[] velocity\n\
325 ================================================================================\n\
326 MSG: std_msgs/Header\n\
327 # Standard metadata for higher-level stamped data types.\n\
328 # This is generally used to communicate timestamped data \n\
329 # in a particular coordinate frame.\n\
331 # sequence ID: consecutively increasing ID \n\
333 #Two-integer timestamp that is expressed as:\n\
334 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
335 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
336 # time-handling sugar is provided by the client library\n\
338 #Frame this data is associated with\n\
357 #endif // YARP_ROSMSG_sensor_msgs_JointState_h
bool writeBare(yarp::os::ConnectionWriter &connection) const override
virtual void appendFloat64(yarp::conf::float64_t data)=0
Send a representation of a 64-bit floating point number to the network connection.
virtual bool read(yarp::os::idl::WireReader &reader)
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
virtual bool isBareMode() const =0
Check if the connection is bare mode.
#define BOTTLE_TAG_STRING
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
std::vector< yarp::conf::float64_t > effort
static constexpr const char * typeText
yarp::os::idl::BottleStyle< yarp::rosmsg::sensor_msgs::JointState > bottleStyle
virtual yarp::conf::float64_t expectFloat64()=0
Read a 64-bit floating point number from the network connection.
virtual bool isError() const =0
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)
std::vector< yarp::conf::float64_t > velocity
An interface for writing to a network connection.
virtual bool isError() const =0
virtual bool convertTextMode()=0
Reads in a standard description in text mode, and converts it to a standard description in binary.
yarp::rosmsg::std_msgs::Header header
yarp::os::Type getType() const override
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.
static constexpr const char * typeChecksum
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to 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.
#define BOTTLE_TAG_FLOAT64
yarp::os::idl::BareStyle< yarp::rosmsg::sensor_msgs::JointState > rosStyle
static constexpr const char * typeName
The main, catch-all namespace for YARP.
bool readBottle(yarp::os::ConnectionReader &connection) override
std::vector< std::string > name
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 expectBlock(char *data, size_t len)=0
Read a block of data from the network connection.
bool readBare(yarp::os::ConnectionReader &connection) override
A single value (typically within a Bottle).
std::vector< yarp::conf::float64_t > position
virtual bool write(const yarp::os::idl::WireWriter &writer) const