00001 #ifndef ros_nav_msgs_Path_h 00002 #define ros_nav_msgs_Path_h 00003 00004 #include <stdint.h> 00005 #include <string.h> 00006 #include <stdlib.h> 00007 #include "../ros/msg.h" 00008 #include "std_msgs/Header.h" 00009 #include "geometry_msgs/PoseStamped.h" 00010 00011 namespace nav_msgs 00012 { 00013 00014 class Path : public ros::Msg 00015 { 00016 public: 00017 std_msgs::Header header; 00018 unsigned char poses_length; 00019 geometry_msgs::PoseStamped st_poses; 00020 geometry_msgs::PoseStamped * poses; 00021 00022 virtual int serialize(unsigned char *outbuffer) 00023 { 00024 int offset = 0; 00025 offset += this->header.serialize(outbuffer + offset); 00026 *(outbuffer + offset++) = poses_length; 00027 *(outbuffer + offset++) = 0; 00028 *(outbuffer + offset++) = 0; 00029 *(outbuffer + offset++) = 0; 00030 for( unsigned char i = 0; i < poses_length; i++){ 00031 offset += this->poses[i].serialize(outbuffer + offset); 00032 } 00033 return offset; 00034 } 00035 00036 virtual int deserialize(unsigned char *inbuffer) 00037 { 00038 int offset = 0; 00039 offset += this->header.deserialize(inbuffer + offset); 00040 unsigned char poses_lengthT = *(inbuffer + offset++); 00041 if(poses_lengthT > poses_length) 00042 this->poses = (geometry_msgs::PoseStamped*)realloc(this->poses, poses_lengthT * sizeof(geometry_msgs::PoseStamped)); 00043 offset += 3; 00044 poses_length = poses_lengthT; 00045 for( unsigned char i = 0; i < poses_length; i++){ 00046 offset += this->st_poses.deserialize(inbuffer + offset); 00047 memcpy( &(this->poses[i]), &(this->st_poses), sizeof(geometry_msgs::PoseStamped)); 00048 } 00049 return offset; 00050 } 00051 00052 const char * getType(){ return "nav_msgs/Path"; }; 00053 00054 }; 00055 00056 } 00057 #endif