modify for Hydro version

Dependencies:   MODSERIAL

Fork of rosserial_mbed_lib by nucho

Committer:
jjzak
Date:
Sat Oct 26 15:39:01 2013 +0000
Revision:
6:3c54bc7badd4
modify for Hydro version;

Who changed what in which revision?

UserRevisionLine numberNew contents of line
jjzak 6:3c54bc7badd4 1 #ifndef _ROS_tf_tfMessage_h
jjzak 6:3c54bc7badd4 2 #define _ROS_tf_tfMessage_h
jjzak 6:3c54bc7badd4 3
jjzak 6:3c54bc7badd4 4 #include <stdint.h>
jjzak 6:3c54bc7badd4 5 #include <string.h>
jjzak 6:3c54bc7badd4 6 #include <stdlib.h>
jjzak 6:3c54bc7badd4 7 #include "ros/msg.h"
jjzak 6:3c54bc7badd4 8 #include "geometry_msgs/TransformStamped.h"
jjzak 6:3c54bc7badd4 9
jjzak 6:3c54bc7badd4 10 namespace tf
jjzak 6:3c54bc7badd4 11 {
jjzak 6:3c54bc7badd4 12
jjzak 6:3c54bc7badd4 13 class tfMessage : public ros::Msg
jjzak 6:3c54bc7badd4 14 {
jjzak 6:3c54bc7badd4 15 public:
jjzak 6:3c54bc7badd4 16 uint8_t transforms_length;
jjzak 6:3c54bc7badd4 17 geometry_msgs::TransformStamped st_transforms;
jjzak 6:3c54bc7badd4 18 geometry_msgs::TransformStamped * transforms;
jjzak 6:3c54bc7badd4 19
jjzak 6:3c54bc7badd4 20 virtual int serialize(unsigned char *outbuffer) const
jjzak 6:3c54bc7badd4 21 {
jjzak 6:3c54bc7badd4 22 int offset = 0;
jjzak 6:3c54bc7badd4 23 *(outbuffer + offset++) = transforms_length;
jjzak 6:3c54bc7badd4 24 *(outbuffer + offset++) = 0;
jjzak 6:3c54bc7badd4 25 *(outbuffer + offset++) = 0;
jjzak 6:3c54bc7badd4 26 *(outbuffer + offset++) = 0;
jjzak 6:3c54bc7badd4 27 for( uint8_t i = 0; i < transforms_length; i++){
jjzak 6:3c54bc7badd4 28 offset += this->transforms[i].serialize(outbuffer + offset);
jjzak 6:3c54bc7badd4 29 }
jjzak 6:3c54bc7badd4 30 return offset;
jjzak 6:3c54bc7badd4 31 }
jjzak 6:3c54bc7badd4 32
jjzak 6:3c54bc7badd4 33 virtual int deserialize(unsigned char *inbuffer)
jjzak 6:3c54bc7badd4 34 {
jjzak 6:3c54bc7badd4 35 int offset = 0;
jjzak 6:3c54bc7badd4 36 uint8_t transforms_lengthT = *(inbuffer + offset++);
jjzak 6:3c54bc7badd4 37 if(transforms_lengthT > transforms_length)
jjzak 6:3c54bc7badd4 38 this->transforms = (geometry_msgs::TransformStamped*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::TransformStamped));
jjzak 6:3c54bc7badd4 39 offset += 3;
jjzak 6:3c54bc7badd4 40 transforms_length = transforms_lengthT;
jjzak 6:3c54bc7badd4 41 for( uint8_t i = 0; i < transforms_length; i++){
jjzak 6:3c54bc7badd4 42 offset += this->st_transforms.deserialize(inbuffer + offset);
jjzak 6:3c54bc7badd4 43 memcpy( &(this->transforms[i]), &(this->st_transforms), sizeof(geometry_msgs::TransformStamped));
jjzak 6:3c54bc7badd4 44 }
jjzak 6:3c54bc7badd4 45 return offset;
jjzak 6:3c54bc7badd4 46 }
jjzak 6:3c54bc7badd4 47
jjzak 6:3c54bc7badd4 48 const char * getType(){ return "tf/tfMessage"; };
jjzak 6:3c54bc7badd4 49 const char * getMD5(){ return "94810edda583a504dfda3829e70d7eec"; };
jjzak 6:3c54bc7badd4 50
jjzak 6:3c54bc7badd4 51 };
jjzak 6:3c54bc7badd4 52
jjzak 6:3c54bc7badd4 53 }
jjzak 6:3c54bc7badd4 54 #endif