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_nav_msgs_Path_h
jjzak 6:3c54bc7badd4 2 #define _ROS_nav_msgs_Path_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 "std_msgs/Header.h"
jjzak 6:3c54bc7badd4 9 #include "geometry_msgs/PoseStamped.h"
jjzak 6:3c54bc7badd4 10
jjzak 6:3c54bc7badd4 11 namespace nav_msgs
jjzak 6:3c54bc7badd4 12 {
jjzak 6:3c54bc7badd4 13
jjzak 6:3c54bc7badd4 14 class Path : public ros::Msg
jjzak 6:3c54bc7badd4 15 {
jjzak 6:3c54bc7badd4 16 public:
jjzak 6:3c54bc7badd4 17 std_msgs::Header header;
jjzak 6:3c54bc7badd4 18 uint8_t poses_length;
jjzak 6:3c54bc7badd4 19 geometry_msgs::PoseStamped st_poses;
jjzak 6:3c54bc7badd4 20 geometry_msgs::PoseStamped * poses;
jjzak 6:3c54bc7badd4 21
jjzak 6:3c54bc7badd4 22 virtual int serialize(unsigned char *outbuffer) const
jjzak 6:3c54bc7badd4 23 {
jjzak 6:3c54bc7badd4 24 int offset = 0;
jjzak 6:3c54bc7badd4 25 offset += this->header.serialize(outbuffer + offset);
jjzak 6:3c54bc7badd4 26 *(outbuffer + offset++) = poses_length;
jjzak 6:3c54bc7badd4 27 *(outbuffer + offset++) = 0;
jjzak 6:3c54bc7badd4 28 *(outbuffer + offset++) = 0;
jjzak 6:3c54bc7badd4 29 *(outbuffer + offset++) = 0;
jjzak 6:3c54bc7badd4 30 for( uint8_t i = 0; i < poses_length; i++){
jjzak 6:3c54bc7badd4 31 offset += this->poses[i].serialize(outbuffer + offset);
jjzak 6:3c54bc7badd4 32 }
jjzak 6:3c54bc7badd4 33 return offset;
jjzak 6:3c54bc7badd4 34 }
jjzak 6:3c54bc7badd4 35
jjzak 6:3c54bc7badd4 36 virtual int deserialize(unsigned char *inbuffer)
jjzak 6:3c54bc7badd4 37 {
jjzak 6:3c54bc7badd4 38 int offset = 0;
jjzak 6:3c54bc7badd4 39 offset += this->header.deserialize(inbuffer + offset);
jjzak 6:3c54bc7badd4 40 uint8_t poses_lengthT = *(inbuffer + offset++);
jjzak 6:3c54bc7badd4 41 if(poses_lengthT > poses_length)
jjzak 6:3c54bc7badd4 42 this->poses = (geometry_msgs::PoseStamped*)realloc(this->poses, poses_lengthT * sizeof(geometry_msgs::PoseStamped));
jjzak 6:3c54bc7badd4 43 offset += 3;
jjzak 6:3c54bc7badd4 44 poses_length = poses_lengthT;
jjzak 6:3c54bc7badd4 45 for( uint8_t i = 0; i < poses_length; i++){
jjzak 6:3c54bc7badd4 46 offset += this->st_poses.deserialize(inbuffer + offset);
jjzak 6:3c54bc7badd4 47 memcpy( &(this->poses[i]), &(this->st_poses), sizeof(geometry_msgs::PoseStamped));
jjzak 6:3c54bc7badd4 48 }
jjzak 6:3c54bc7badd4 49 return offset;
jjzak 6:3c54bc7badd4 50 }
jjzak 6:3c54bc7badd4 51
jjzak 6:3c54bc7badd4 52 const char * getType(){ return "nav_msgs/Path"; };
jjzak 6:3c54bc7badd4 53 const char * getMD5(){ return "6227e2b7e9cce15051f669a5e197bbf7"; };
jjzak 6:3c54bc7badd4 54
jjzak 6:3c54bc7badd4 55 };
jjzak 6:3c54bc7badd4 56
jjzak 6:3c54bc7badd4 57 }
jjzak 6:3c54bc7badd4 58 #endif