Go to the documentation of this file.00001 #ifndef ros_SERVICE_GetPlan_h
00002 #define ros_SERVICE_GetPlan_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 #include "nav_msgs/Path.h"
00009
00010 namespace nav_msgs
00011 {
00012
00013 static const char GETPLAN[] = "nav_msgs/GetPlan";
00014
00015 class GetPlanRequest : public ros::Msg
00016 {
00017 public:
00018 geometry_msgs::PoseStamped start;
00019 geometry_msgs::PoseStamped goal;
00020 float tolerance;
00021
00022 virtual int serialize(unsigned char *outbuffer)
00023 {
00024 int offset = 0;
00025 offset += this->start.serialize(outbuffer + offset);
00026 offset += this->goal.serialize(outbuffer + offset);
00027 union {
00028 float real;
00029 unsigned long base;
00030 } u_tolerance;
00031 u_tolerance.real = this->tolerance;
00032 *(outbuffer + offset + 0) = (u_tolerance.base >> (8 * 0)) & 0xFF;
00033 *(outbuffer + offset + 1) = (u_tolerance.base >> (8 * 1)) & 0xFF;
00034 *(outbuffer + offset + 2) = (u_tolerance.base >> (8 * 2)) & 0xFF;
00035 *(outbuffer + offset + 3) = (u_tolerance.base >> (8 * 3)) & 0xFF;
00036 offset += sizeof(this->tolerance);
00037 return offset;
00038 }
00039
00040 virtual int deserialize(unsigned char *inbuffer)
00041 {
00042 int offset = 0;
00043 offset += this->start.deserialize(inbuffer + offset);
00044 offset += this->goal.deserialize(inbuffer + offset);
00045 union {
00046 float real;
00047 unsigned long base;
00048 } u_tolerance;
00049 u_tolerance.base = 0;
00050 u_tolerance.base |= ((typeof(u_tolerance.base)) (*(inbuffer + offset + 0))) << (8 * 0);
00051 u_tolerance.base |= ((typeof(u_tolerance.base)) (*(inbuffer + offset + 1))) << (8 * 1);
00052 u_tolerance.base |= ((typeof(u_tolerance.base)) (*(inbuffer + offset + 2))) << (8 * 2);
00053 u_tolerance.base |= ((typeof(u_tolerance.base)) (*(inbuffer + offset + 3))) << (8 * 3);
00054 this->tolerance = u_tolerance.real;
00055 offset += sizeof(this->tolerance);
00056 return offset;
00057 }
00058
00059 const char * getType(){ return GETPLAN; };
00060
00061 };
00062
00063 class GetPlanResponse : public ros::Msg
00064 {
00065 public:
00066 nav_msgs::Path plan;
00067
00068 virtual int serialize(unsigned char *outbuffer)
00069 {
00070 int offset = 0;
00071 offset += this->plan.serialize(outbuffer + offset);
00072 return offset;
00073 }
00074
00075 virtual int deserialize(unsigned char *inbuffer)
00076 {
00077 int offset = 0;
00078 offset += this->plan.deserialize(inbuffer + offset);
00079 return offset;
00080 }
00081
00082 const char * getType(){ return GETPLAN; };
00083
00084 };
00085
00086 }
00087 #endif