GetSearchPosition.h
Go to the documentation of this file.
00001 #ifndef _ROS_SERVICE_GetSearchPosition_h
00002 #define _ROS_SERVICE_GetSearchPosition_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 hector_nav_msgs
00010 {
00011 
00012 static const char GETSEARCHPOSITION[] = "hector_nav_msgs/GetSearchPosition";
00013 
00014   class GetSearchPositionRequest : public ros::Msg
00015   {
00016     public:
00017       geometry_msgs::PoseStamped ooi_pose;
00018       float distance;
00019 
00020     virtual int serialize(unsigned char *outbuffer) const
00021     {
00022       int offset = 0;
00023       offset += this->ooi_pose.serialize(outbuffer + offset);
00024       union {
00025         float real;
00026         uint32_t base;
00027       } u_distance;
00028       u_distance.real = this->distance;
00029       *(outbuffer + offset + 0) = (u_distance.base >> (8 * 0)) & 0xFF;
00030       *(outbuffer + offset + 1) = (u_distance.base >> (8 * 1)) & 0xFF;
00031       *(outbuffer + offset + 2) = (u_distance.base >> (8 * 2)) & 0xFF;
00032       *(outbuffer + offset + 3) = (u_distance.base >> (8 * 3)) & 0xFF;
00033       offset += sizeof(this->distance);
00034       return offset;
00035     }
00036 
00037     virtual int deserialize(unsigned char *inbuffer)
00038     {
00039       int offset = 0;
00040       offset += this->ooi_pose.deserialize(inbuffer + offset);
00041       union {
00042         float real;
00043         uint32_t base;
00044       } u_distance;
00045       u_distance.base = 0;
00046       u_distance.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00047       u_distance.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00048       u_distance.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00049       u_distance.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00050       this->distance = u_distance.real;
00051       offset += sizeof(this->distance);
00052      return offset;
00053     }
00054 
00055     const char * getType(){ return GETSEARCHPOSITION; };
00056     const char * getMD5(){ return "a579e8b989d066f6c17946ab060a6ff9"; };
00057 
00058   };
00059 
00060   class GetSearchPositionResponse : public ros::Msg
00061   {
00062     public:
00063       geometry_msgs::PoseStamped search_pose;
00064 
00065     virtual int serialize(unsigned char *outbuffer) const
00066     {
00067       int offset = 0;
00068       offset += this->search_pose.serialize(outbuffer + offset);
00069       return offset;
00070     }
00071 
00072     virtual int deserialize(unsigned char *inbuffer)
00073     {
00074       int offset = 0;
00075       offset += this->search_pose.deserialize(inbuffer + offset);
00076      return offset;
00077     }
00078 
00079     const char * getType(){ return GETSEARCHPOSITION; };
00080     const char * getMD5(){ return "6cc90c22cc49490b4dd1ef4798491231"; };
00081 
00082   };
00083 
00084   class GetSearchPosition {
00085     public:
00086     typedef GetSearchPositionRequest Request;
00087     typedef GetSearchPositionResponse Response;
00088   };
00089 
00090 }
00091 #endif


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