Personal fork
Fork of rosserial_mbed_lib by
nav_msgs/Path.h
- Committer:
- nucho
- Date:
- 2011-11-12
- Revision:
- 3:1cf99502f396
- Parent:
- 1:ff0ec969dad1
File content as of revision 3:1cf99502f396:
#ifndef _ROS_nav_msgs_Path_h #define _ROS_nav_msgs_Path_h #include <stdint.h> #include <string.h> #include <stdlib.h> #include "ros/msg.h" #include "std_msgs/Header.h" #include "geometry_msgs/PoseStamped.h" namespace nav_msgs { class Path : public ros::Msg { public: std_msgs::Header header; uint8_t poses_length; geometry_msgs::PoseStamped st_poses; geometry_msgs::PoseStamped * poses; virtual int serialize(unsigned char *outbuffer) const { int offset = 0; offset += this->header.serialize(outbuffer + offset); *(outbuffer + offset++) = poses_length; *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; for( uint8_t i = 0; i < poses_length; i++){ offset += this->poses[i].serialize(outbuffer + offset); } return offset; } virtual int deserialize(unsigned char *inbuffer) { int offset = 0; offset += this->header.deserialize(inbuffer + offset); uint8_t poses_lengthT = *(inbuffer + offset++); if(poses_lengthT > poses_length) this->poses = (geometry_msgs::PoseStamped*)realloc(this->poses, poses_lengthT * sizeof(geometry_msgs::PoseStamped)); offset += 3; poses_length = poses_lengthT; for( uint8_t i = 0; i < poses_length; i++){ offset += this->st_poses.deserialize(inbuffer + offset); memcpy( &(this->poses[i]), &(this->st_poses), sizeof(geometry_msgs::PoseStamped)); } return offset; } virtual const char * getType(){ return "nav_msgs/Path"; }; virtual const char * getMD5(){ return "6227e2b7e9cce15051f669a5e197bbf7"; }; }; } #endif