MakeNavPlan.h
Go to the documentation of this file.
00001 #ifndef _ROS_SERVICE_MakeNavPlan_h
00002 #define _ROS_SERVICE_MakeNavPlan_h
00003 #include <stdint.h>
00004 #include <string.h>
00005 #include <stdlib.h>
00006 #include "ros/msg.h"
00007 #include "geometry_msgs/PoseStamped.h"
00008 
00009 namespace navfn
00010 {
00011 
00012 static const char MAKENAVPLAN[] = "navfn/MakeNavPlan";
00013 
00014   class MakeNavPlanRequest : public ros::Msg
00015   {
00016     public:
00017       geometry_msgs::PoseStamped start;
00018       geometry_msgs::PoseStamped goal;
00019 
00020     virtual int serialize(unsigned char *outbuffer) const
00021     {
00022       int offset = 0;
00023       offset += this->start.serialize(outbuffer + offset);
00024       offset += this->goal.serialize(outbuffer + offset);
00025       return offset;
00026     }
00027 
00028     virtual int deserialize(unsigned char *inbuffer)
00029     {
00030       int offset = 0;
00031       offset += this->start.deserialize(inbuffer + offset);
00032       offset += this->goal.deserialize(inbuffer + offset);
00033      return offset;
00034     }
00035 
00036     const char * getType(){ return MAKENAVPLAN; };
00037     const char * getMD5(){ return "2fe3126bd5b2d56edd5005220333d4fd"; };
00038 
00039   };
00040 
00041   class MakeNavPlanResponse : public ros::Msg
00042   {
00043     public:
00044       uint8_t plan_found;
00045       char * error_message;
00046       uint8_t path_length;
00047       geometry_msgs::PoseStamped st_path;
00048       geometry_msgs::PoseStamped * path;
00049 
00050     virtual int serialize(unsigned char *outbuffer) const
00051     {
00052       int offset = 0;
00053       *(outbuffer + offset + 0) = (this->plan_found >> (8 * 0)) & 0xFF;
00054       offset += sizeof(this->plan_found);
00055       uint32_t length_error_message = strlen( (const char*) this->error_message);
00056       memcpy(outbuffer + offset, &length_error_message, sizeof(uint32_t));
00057       offset += 4;
00058       memcpy(outbuffer + offset, this->error_message, length_error_message);
00059       offset += length_error_message;
00060       *(outbuffer + offset++) = path_length;
00061       *(outbuffer + offset++) = 0;
00062       *(outbuffer + offset++) = 0;
00063       *(outbuffer + offset++) = 0;
00064       for( uint8_t i = 0; i < path_length; i++){
00065       offset += this->path[i].serialize(outbuffer + offset);
00066       }
00067       return offset;
00068     }
00069 
00070     virtual int deserialize(unsigned char *inbuffer)
00071     {
00072       int offset = 0;
00073       this->plan_found =  ((uint8_t) (*(inbuffer + offset)));
00074       offset += sizeof(this->plan_found);
00075       uint32_t length_error_message;
00076       memcpy(&length_error_message, (inbuffer + offset), sizeof(uint32_t));
00077       offset += 4;
00078       for(unsigned int k= offset; k< offset+length_error_message; ++k){
00079           inbuffer[k-1]=inbuffer[k];
00080       }
00081       inbuffer[offset+length_error_message-1]=0;
00082       this->error_message = (char *)(inbuffer + offset-1);
00083       offset += length_error_message;
00084       uint8_t path_lengthT = *(inbuffer + offset++);
00085       if(path_lengthT > path_length)
00086         this->path = (geometry_msgs::PoseStamped*)realloc(this->path, path_lengthT * sizeof(geometry_msgs::PoseStamped));
00087       offset += 3;
00088       path_length = path_lengthT;
00089       for( uint8_t i = 0; i < path_length; i++){
00090       offset += this->st_path.deserialize(inbuffer + offset);
00091         memcpy( &(this->path[i]), &(this->st_path), sizeof(geometry_msgs::PoseStamped));
00092       }
00093      return offset;
00094     }
00095 
00096     const char * getType(){ return MAKENAVPLAN; };
00097     const char * getMD5(){ return "8b8ed7edf1b237dc9ddda8c8ffed5d3a"; };
00098 
00099   };
00100 
00101   class MakeNavPlan {
00102     public:
00103     typedef MakeNavPlanRequest Request;
00104     typedef MakeNavPlanResponse Response;
00105   };
00106 
00107 }
00108 #endif


lizi_arduino
Author(s): RoboTiCan
autogenerated on Wed Aug 26 2015 12:24:22