Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Fork of ros_lib_kinetic by
tf/tfMessage.h
- Committer:
- jvfausto
- Date:
- 2018-11-02
- Revision:
- 2:2e7b61982dd2
- Parent:
- 0:9e9b7db60fd5
File content as of revision 2:2e7b61982dd2:
#ifndef _ROS_tf_tfMessage_h #define _ROS_tf_tfMessage_h #include <stdint.h> #include <string.h> #include <stdlib.h> #include "ros/msg.h" #include "geometry_msgs/TransformStamped.h" namespace tf { class tfMessage : public ros::Msg { public: uint32_t transforms_length; typedef geometry_msgs::TransformStamped _transforms_type; _transforms_type st_transforms; _transforms_type * transforms; tfMessage(): transforms_length(0), transforms(NULL) { } virtual int serialize(unsigned char *outbuffer) const { int offset = 0; *(outbuffer + offset + 0) = (this->transforms_length >> (8 * 0)) & 0xFF; *(outbuffer + offset + 1) = (this->transforms_length >> (8 * 1)) & 0xFF; *(outbuffer + offset + 2) = (this->transforms_length >> (8 * 2)) & 0xFF; *(outbuffer + offset + 3) = (this->transforms_length >> (8 * 3)) & 0xFF; offset += sizeof(this->transforms_length); for( uint32_t i = 0; i < transforms_length; i++){ offset += this->transforms[i].serialize(outbuffer + offset); } return offset; } virtual int deserialize(unsigned char *inbuffer) { int offset = 0; uint32_t transforms_lengthT = ((uint32_t) (*(inbuffer + offset))); transforms_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); transforms_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); transforms_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); offset += sizeof(this->transforms_length); if(transforms_lengthT > transforms_length) this->transforms = (geometry_msgs::TransformStamped*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::TransformStamped)); transforms_length = transforms_lengthT; for( uint32_t i = 0; i < transforms_length; i++){ offset += this->st_transforms.deserialize(inbuffer + offset); memcpy( &(this->transforms[i]), &(this->st_transforms), sizeof(geometry_msgs::TransformStamped)); } return offset; } const char * getType(){ return "tf/tfMessage"; }; const char * getMD5(){ return "94810edda583a504dfda3829e70d7eec"; }; }; } #endif