QueryPlannerInterfaces.h
Go to the documentation of this file.
00001 #ifndef _ROS_SERVICE_QueryPlannerInterfaces_h
00002 #define _ROS_SERVICE_QueryPlannerInterfaces_h
00003 #include <stdint.h>
00004 #include <string.h>
00005 #include <stdlib.h>
00006 #include "ros/msg.h"
00007 #include "moveit_msgs/PlannerInterfaceDescription.h"
00008 
00009 namespace moveit_msgs
00010 {
00011 
00012 static const char QUERYPLANNERINTERFACES[] = "moveit_msgs/QueryPlannerInterfaces";
00013 
00014   class QueryPlannerInterfacesRequest : public ros::Msg
00015   {
00016     public:
00017 
00018     virtual int serialize(unsigned char *outbuffer) const
00019     {
00020       int offset = 0;
00021       return offset;
00022     }
00023 
00024     virtual int deserialize(unsigned char *inbuffer)
00025     {
00026       int offset = 0;
00027      return offset;
00028     }
00029 
00030     const char * getType(){ return QUERYPLANNERINTERFACES; };
00031     const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
00032 
00033   };
00034 
00035   class QueryPlannerInterfacesResponse : public ros::Msg
00036   {
00037     public:
00038       uint8_t planner_interfaces_length;
00039       moveit_msgs::PlannerInterfaceDescription st_planner_interfaces;
00040       moveit_msgs::PlannerInterfaceDescription * planner_interfaces;
00041 
00042     virtual int serialize(unsigned char *outbuffer) const
00043     {
00044       int offset = 0;
00045       *(outbuffer + offset++) = planner_interfaces_length;
00046       *(outbuffer + offset++) = 0;
00047       *(outbuffer + offset++) = 0;
00048       *(outbuffer + offset++) = 0;
00049       for( uint8_t i = 0; i < planner_interfaces_length; i++){
00050       offset += this->planner_interfaces[i].serialize(outbuffer + offset);
00051       }
00052       return offset;
00053     }
00054 
00055     virtual int deserialize(unsigned char *inbuffer)
00056     {
00057       int offset = 0;
00058       uint8_t planner_interfaces_lengthT = *(inbuffer + offset++);
00059       if(planner_interfaces_lengthT > planner_interfaces_length)
00060         this->planner_interfaces = (moveit_msgs::PlannerInterfaceDescription*)realloc(this->planner_interfaces, planner_interfaces_lengthT * sizeof(moveit_msgs::PlannerInterfaceDescription));
00061       offset += 3;
00062       planner_interfaces_length = planner_interfaces_lengthT;
00063       for( uint8_t i = 0; i < planner_interfaces_length; i++){
00064       offset += this->st_planner_interfaces.deserialize(inbuffer + offset);
00065         memcpy( &(this->planner_interfaces[i]), &(this->st_planner_interfaces), sizeof(moveit_msgs::PlannerInterfaceDescription));
00066       }
00067      return offset;
00068     }
00069 
00070     const char * getType(){ return QUERYPLANNERINTERFACES; };
00071     const char * getMD5(){ return "acd3317a4c5631f33127fb428209db05"; };
00072 
00073   };
00074 
00075   class QueryPlannerInterfaces {
00076     public:
00077     typedef QueryPlannerInterfacesRequest Request;
00078     typedef QueryPlannerInterfacesResponse Response;
00079   };
00080 
00081 }
00082 #endif


ric_mc
Author(s): RoboTiCan
autogenerated on Thu Aug 27 2015 14:39:50