00001 #ifndef _ROS_SERVICE_GetDistanceToObstacle_h 00002 #define _ROS_SERVICE_GetDistanceToObstacle_h 00003 #include <stdint.h> 00004 #include <string.h> 00005 #include <stdlib.h> 00006 #include "ros/msg.h" 00007 #include "geometry_msgs/PointStamped.h" 00008 00009 namespace hector_nav_msgs 00010 { 00011 00012 static const char GETDISTANCETOOBSTACLE[] = "hector_nav_msgs/GetDistanceToObstacle"; 00013 00014 class GetDistanceToObstacleRequest : public ros::Msg 00015 { 00016 public: 00017 geometry_msgs::PointStamped point; 00018 00019 virtual int serialize(unsigned char *outbuffer) const 00020 { 00021 int offset = 0; 00022 offset += this->point.serialize(outbuffer + offset); 00023 return offset; 00024 } 00025 00026 virtual int deserialize(unsigned char *inbuffer) 00027 { 00028 int offset = 0; 00029 offset += this->point.deserialize(inbuffer + offset); 00030 return offset; 00031 } 00032 00033 const char * getType(){ return GETDISTANCETOOBSTACLE; }; 00034 const char * getMD5(){ return "47dfdbd810b48d0a47b7ad67e4191bcc"; }; 00035 00036 }; 00037 00038 class GetDistanceToObstacleResponse : public ros::Msg 00039 { 00040 public: 00041 float distance; 00042 geometry_msgs::PointStamped end_point; 00043 00044 virtual int serialize(unsigned char *outbuffer) const 00045 { 00046 int offset = 0; 00047 union { 00048 float real; 00049 uint32_t base; 00050 } u_distance; 00051 u_distance.real = this->distance; 00052 *(outbuffer + offset + 0) = (u_distance.base >> (8 * 0)) & 0xFF; 00053 *(outbuffer + offset + 1) = (u_distance.base >> (8 * 1)) & 0xFF; 00054 *(outbuffer + offset + 2) = (u_distance.base >> (8 * 2)) & 0xFF; 00055 *(outbuffer + offset + 3) = (u_distance.base >> (8 * 3)) & 0xFF; 00056 offset += sizeof(this->distance); 00057 offset += this->end_point.serialize(outbuffer + offset); 00058 return offset; 00059 } 00060 00061 virtual int deserialize(unsigned char *inbuffer) 00062 { 00063 int offset = 0; 00064 union { 00065 float real; 00066 uint32_t base; 00067 } u_distance; 00068 u_distance.base = 0; 00069 u_distance.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00070 u_distance.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00071 u_distance.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00072 u_distance.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00073 this->distance = u_distance.real; 00074 offset += sizeof(this->distance); 00075 offset += this->end_point.deserialize(inbuffer + offset); 00076 return offset; 00077 } 00078 00079 const char * getType(){ return GETDISTANCETOOBSTACLE; }; 00080 const char * getMD5(){ return "019a8fc3bf7fd73c014dc08523397f1c"; }; 00081 00082 }; 00083 00084 class GetDistanceToObstacle { 00085 public: 00086 typedef GetDistanceToObstacleRequest Request; 00087 typedef GetDistanceToObstacleResponse Response; 00088 }; 00089 00090 } 00091 #endif