Just changed OUTPUT_SIZE and INPUT_SIZE in ros/node_handle.h

Dependencies:   BufferedSerial

Dependents:   WRS2020_mecanum_node

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers GetPlan.h Source File

GetPlan.h

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       typedef geometry_msgs::PoseStamped _start_type;
00019       _start_type start;
00020       typedef geometry_msgs::PoseStamped _goal_type;
00021       _goal_type goal;
00022       typedef float _tolerance_type;
00023       _tolerance_type tolerance;
00024 
00025     GetPlanRequest():
00026       start(),
00027       goal(),
00028       tolerance(0)
00029     {
00030     }
00031 
00032     virtual int serialize(unsigned char *outbuffer) const
00033     {
00034       int offset = 0;
00035       offset += this->start.serialize(outbuffer + offset);
00036       offset += this->goal.serialize(outbuffer + offset);
00037       union {
00038         float real;
00039         uint32_t base;
00040       } u_tolerance;
00041       u_tolerance.real = this->tolerance;
00042       *(outbuffer + offset + 0) = (u_tolerance.base >> (8 * 0)) & 0xFF;
00043       *(outbuffer + offset + 1) = (u_tolerance.base >> (8 * 1)) & 0xFF;
00044       *(outbuffer + offset + 2) = (u_tolerance.base >> (8 * 2)) & 0xFF;
00045       *(outbuffer + offset + 3) = (u_tolerance.base >> (8 * 3)) & 0xFF;
00046       offset += sizeof(this->tolerance);
00047       return offset;
00048     }
00049 
00050     virtual int deserialize(unsigned char *inbuffer)
00051     {
00052       int offset = 0;
00053       offset += this->start.deserialize(inbuffer + offset);
00054       offset += this->goal.deserialize(inbuffer + offset);
00055       union {
00056         float real;
00057         uint32_t base;
00058       } u_tolerance;
00059       u_tolerance.base = 0;
00060       u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00061       u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00062       u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00063       u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00064       this->tolerance = u_tolerance.real;
00065       offset += sizeof(this->tolerance);
00066      return offset;
00067     }
00068 
00069     const char * getType(){ return GETPLAN; };
00070     const char * getMD5(){ return "e25a43e0752bcca599a8c2eef8282df8"; };
00071 
00072   };
00073 
00074   class GetPlanResponse : public ros::Msg
00075   {
00076     public:
00077       typedef nav_msgs::Path _plan_type;
00078       _plan_type plan;
00079 
00080     GetPlanResponse():
00081       plan()
00082     {
00083     }
00084 
00085     virtual int serialize(unsigned char *outbuffer) const
00086     {
00087       int offset = 0;
00088       offset += this->plan.serialize(outbuffer + offset);
00089       return offset;
00090     }
00091 
00092     virtual int deserialize(unsigned char *inbuffer)
00093     {
00094       int offset = 0;
00095       offset += this->plan.deserialize(inbuffer + offset);
00096      return offset;
00097     }
00098 
00099     const char * getType(){ return GETPLAN; };
00100     const char * getMD5(){ return "0002bc113c0259d71f6cf8cbc9430e18"; };
00101 
00102   };
00103 
00104   class GetPlan {
00105     public:
00106     typedef GetPlanRequest Request;
00107     typedef GetPlanResponse Response;
00108   };
00109 
00110 }
00111 #endif