41 #ifndef YARP_ROSMSG_sensor_msgs_MultiDOFJointState_h 42 #define YARP_ROSMSG_sensor_msgs_MultiDOFJointState_h 63 std::vector<yarp::rosmsg::geometry_msgs::Transform>
transforms;
64 std::vector<yarp::rosmsg::geometry_msgs::Twist>
twist;
65 std::vector<yarp::rosmsg::geometry_msgs::Wrench>
wrench;
97 if (!header.
read(connection)) {
103 joint_names.resize(len);
104 for (
int i=0; i<len; i++) {
106 joint_names[i].resize(len2);
107 if (!connection.
expectBlock((
char*)joint_names[i].c_str(), len2)) {
114 transforms.resize(len);
115 for (
int i=0; i<len; i++) {
116 if (!transforms[i].
read(connection)) {
124 for (
int i=0; i<len; i++) {
125 if (!twist[i].
read(connection)) {
133 for (
int i=0; i<len; i++) {
134 if (!wrench[i].
read(connection)) {
151 if (!header.
read(connection)) {
160 joint_names.resize(len);
161 for (
int i=0; i<len; i++) {
163 joint_names[i].resize(len2);
164 if (!connection.
expectBlock((
char*)joint_names[i].c_str(), len2)) {
174 transforms.resize(len);
175 for (
int i=0; i<len; i++) {
176 if (!transforms[i].
read(connection)) {
187 for (
int i=0; i<len; i++) {
188 if (!twist[i].
read(connection)) {
199 for (
int i=0; i<len; i++) {
200 if (!wrench[i].
read(connection)) {
218 if (!header.
write(connection)) {
224 for (
size_t i=0; i<joint_names.size(); i++) {
231 for (
size_t i=0; i<transforms.size(); i++) {
232 if (!transforms[i].
write(connection)) {
239 for (
size_t i=0; i<twist.size(); i++) {
240 if (!twist[i].
write(connection)) {
247 for (
size_t i=0; i<wrench.size(); i++) {
248 if (!wrench[i].
write(connection)) {
262 if (!header.
write(connection)) {
269 for (
size_t i=0; i<joint_names.size(); i++) {
277 for (
size_t i=0; i<transforms.size(); i++) {
278 if (!transforms[i].
write(connection)) {
286 for (
size_t i=0; i<twist.size(); i++) {
287 if (!twist[i].
write(connection)) {
295 for (
size_t i=0; i<wrench.size(); i++) {
296 if (!wrench[i].
write(connection)) {
318 static constexpr
const char*
typeName =
"sensor_msgs/MultiDOFJointState";
321 static constexpr
const char*
typeChecksum =
"690f272f0640d2631c305eeb8301e59d";
325 # Representation of state for joints with multiple degrees of freedom, \n\ 326 # following the structure of JointState.\n\ 328 # It is assumed that a joint in a system corresponds to a transform that gets applied \n\ 329 # along the kinematic chain. For example, a planar joint (as in URDF) is 3DOF (x, y, yaw)\n\ 330 # and those 3DOF can be expressed as a transformation matrix, and that transformation\n\ 331 # matrix can be converted back to (x, y, yaw)\n\ 333 # Each joint is uniquely identified by its name\n\ 334 # The header specifies the time at which the joint states were recorded. All the joint states\n\ 335 # in one message have to be recorded at the same time.\n\ 337 # This message consists of a multiple arrays, one for each part of the joint state. \n\ 338 # The goal is to make each of the fields optional. When e.g. your joints have no\n\ 339 # wrench associated with them, you can leave the wrench array empty. \n\ 341 # All arrays in this message should have the same size, or be empty.\n\ 342 # This is the only way to uniquely associate the joint name with the correct\n\ 347 string[] joint_names\n\ 348 geometry_msgs/Transform[] transforms\n\ 349 geometry_msgs/Twist[] twist\n\ 350 geometry_msgs/Wrench[] wrench\n\ 352 ================================================================================\n\ 353 MSG: std_msgs/Header\n\ 354 # Standard metadata for higher-level stamped data types.\n\ 355 # This is generally used to communicate timestamped data \n\ 356 # in a particular coordinate frame.\n\ 358 # sequence ID: consecutively increasing ID \n\ 360 #Two-integer timestamp that is expressed as:\n\ 361 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ 362 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ 363 # time-handling sugar is provided by the client library\n\ 365 #Frame this data is associated with\n\ 370 ================================================================================\n\ 371 MSG: geometry_msgs/Transform\n\ 372 # This represents the transform between two coordinate frames in free space.\n\ 374 Vector3 translation\n\ 375 Quaternion rotation\n\ 377 ================================================================================\n\ 378 MSG: geometry_msgs/Vector3\n\ 379 # This represents a vector in free space. \n\ 380 # It is only meant to represent a direction. Therefore, it does not\n\ 381 # make sense to apply a translation to it (e.g., when applying a \n\ 382 # generic rigid transformation to a Vector3, tf2 will only apply the\n\ 383 # rotation). If you want your data to be translatable too, use the\n\ 384 # geometry_msgs/Point message instead.\n\ 389 ================================================================================\n\ 390 MSG: geometry_msgs/Quaternion\n\ 391 # This represents an orientation in free space in quaternion form.\n\ 398 ================================================================================\n\ 399 MSG: geometry_msgs/Twist\n\ 400 # This expresses velocity in free space broken into its linear and angular parts.\n\ 404 ================================================================================\n\ 405 MSG: geometry_msgs/Wrench\n\ 406 # This represents force in free space, separated into\n\ 407 # its linear and angular parts.\n\ 425 #endif // YARP_ROSMSG_sensor_msgs_MultiDOFJointState_h
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
bool readBottle(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.
std::vector< yarp::rosmsg::geometry_msgs::Twist > twist
#define BOTTLE_TAG_STRING
virtual bool expectBlock(char *data, size_t len)=0
Read a block of data from the network connection.
yarp::os::idl::BottleStyle< yarp::rosmsg::sensor_msgs::MultiDOFJointState > bottleStyle
static Type byName(const char *name)
Type & addProperty(const char *key, const Value &val)
yarp::os::Type getType() const override
static constexpr const char * typeText
virtual bool isError() const =0
std::vector< std::string > joint_names
The main, catch-all namespace for YARP.
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...
std::vector< yarp::rosmsg::geometry_msgs::Transform > transforms
virtual bool isBareMode() const =0
Check if the connection is bare mode.
An interface for writing to a network connection.
virtual bool write(const yarp::os::idl::WireWriter &writer) const
virtual void appendInt32(std::int32_t data)=0
Send a representation of a 32-bit integer to the network connection.
std::vector< yarp::rosmsg::geometry_msgs::Wrench > wrench
bool writeBare(yarp::os::ConnectionWriter &connection) const override
virtual bool read(yarp::os::idl::WireReader &reader)
yarp::rosmsg::std_msgs::Header header
virtual bool isError() const =0
A "tamed" Portable, that promises to serialize itself in an IDL-friendly way.
virtual std::int32_t expectInt32()=0
Read a 32-bit integer from the network connection.
An interface for reading from a network connection.
yarp::os::idl::BareStyle< yarp::rosmsg::sensor_msgs::MultiDOFJointState > rosStyle
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
A single value (typically within a Bottle).
static constexpr const char * typeChecksum
virtual bool isBareMode() const =0
Check if the connection is bare mode.
virtual bool convertTextMode()=0
Converts a standard description in binary into a textual description, if the connection is in text-mo...
bool readBare(yarp::os::ConnectionReader &connection) override
IDL-friendly connection reader.
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.