38 #ifndef YARP_ROSMSG_sensor_msgs_JointState_h
39 #define YARP_ROSMSG_sensor_msgs_JointState_h
56 std::vector<std::string>
name;
59 std::vector<yarp::conf::float64_t>
effort;
98 for (
int i=0; i<len; i++) {
100 name[i].resize(len2);
149 for (
int i=0; i<len; i++) {
151 name[i].resize(len2);
163 for (
int i=0; i<len; i++) {
173 for (
int i=0; i<len; i++) {
183 for (
int i=0; i<len; i++) {
206 for (
size_t i=0; i<
name.size(); i++) {
245 for (
size_t i=0; i<
name.size(); i++) {
253 for (
size_t i=0; i<
position.size(); i++) {
260 for (
size_t i=0; i<
velocity.size(); i++) {
267 for (
size_t i=0; i<
effort.size(); i++) {
288 static constexpr
const char*
typeName =
"sensor_msgs/JointState";
291 static constexpr
const char*
typeChecksum =
"3066dcd76a6cfaef579bd0f34173e9fd";
295 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\
297 # The state of each joint (revolute or prismatic) is defined by:\n\
298 # * the position of the joint (rad or m),\n\
299 # * the velocity of the joint (rad/s or m/s) and \n\
300 # * the effort that is applied in the joint (Nm or N).\n\
302 # Each joint is uniquely identified by its name\n\
303 # The header specifies the time at which the joint states were recorded. All the joint states\n\
304 # in one message have to be recorded at the same time.\n\
306 # This message consists of a multiple arrays, one for each part of the joint state. \n\
307 # The goal is to make each of the fields optional. When e.g. your joints have no\n\
308 # effort associated with them, you can leave the effort array empty. \n\
310 # All arrays in this message should have the same size, or be empty.\n\
311 # This is the only way to uniquely associate the joint name with the correct\n\
318 float64[] position\n\
319 float64[] velocity\n\
322 ================================================================================\n\
323 MSG: std_msgs/Header\n\
324 # Standard metadata for higher-level stamped data types.\n\
325 # This is generally used to communicate timestamped data \n\
326 # in a particular coordinate frame.\n\
328 # sequence ID: consecutively increasing ID \n\
330 #Two-integer timestamp that is expressed as:\n\
331 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
332 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
333 # time-handling sugar is provided by the client library\n\
335 #Frame this data is associated with\n\
#define BOTTLE_TAG_FLOAT64
#define BOTTLE_TAG_STRING
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.
static constexpr const char * typeName
std::vector< std::string > name
static constexpr const char * typeText
bool writeBare(yarp::os::ConnectionWriter &connection) const override
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
static constexpr const char * typeChecksum
bool readBottle(yarp::os::ConnectionReader &connection) override
std::vector< yarp::conf::float64_t > position
std::vector< yarp::conf::float64_t > velocity
bool readBare(yarp::os::ConnectionReader &connection) override
yarp::os::idl::BareStyle< yarp::rosmsg::sensor_msgs::JointState > rosStyle
yarp::os::idl::BottleStyle< yarp::rosmsg::sensor_msgs::JointState > bottleStyle
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
std::vector< yarp::conf::float64_t > effort
yarp::os::Type getType() const override
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
yarp::rosmsg::std_msgs::Header header
The main, catch-all namespace for YARP.