modify for Hydro version

Dependencies:   MODSERIAL

Fork of rosserial_mbed_lib by nucho

Committer:
jjzak
Date:
Sat Oct 26 15:39:01 2013 +0000
Revision:
6:3c54bc7badd4
modify for Hydro version;

Who changed what in which revision?

UserRevisionLine numberNew contents of line
jjzak 6:3c54bc7badd4 1 #ifndef _ROS_SERVICE_GetPlan_h
jjzak 6:3c54bc7badd4 2 #define _ROS_SERVICE_GetPlan_h
jjzak 6:3c54bc7badd4 3 #include <stdint.h>
jjzak 6:3c54bc7badd4 4 #include <string.h>
jjzak 6:3c54bc7badd4 5 #include <stdlib.h>
jjzak 6:3c54bc7badd4 6 #include "ros/msg.h"
jjzak 6:3c54bc7badd4 7 #include "geometry_msgs/PoseStamped.h"
jjzak 6:3c54bc7badd4 8 #include "nav_msgs/Path.h"
jjzak 6:3c54bc7badd4 9
jjzak 6:3c54bc7badd4 10 namespace nav_msgs
jjzak 6:3c54bc7badd4 11 {
jjzak 6:3c54bc7badd4 12
jjzak 6:3c54bc7badd4 13 static const char GETPLAN[] = "nav_msgs/GetPlan";
jjzak 6:3c54bc7badd4 14
jjzak 6:3c54bc7badd4 15 class GetPlanRequest : public ros::Msg
jjzak 6:3c54bc7badd4 16 {
jjzak 6:3c54bc7badd4 17 public:
jjzak 6:3c54bc7badd4 18 geometry_msgs::PoseStamped start;
jjzak 6:3c54bc7badd4 19 geometry_msgs::PoseStamped goal;
jjzak 6:3c54bc7badd4 20 float tolerance;
jjzak 6:3c54bc7badd4 21
jjzak 6:3c54bc7badd4 22 virtual int serialize(unsigned char *outbuffer) const
jjzak 6:3c54bc7badd4 23 {
jjzak 6:3c54bc7badd4 24 int offset = 0;
jjzak 6:3c54bc7badd4 25 offset += this->start.serialize(outbuffer + offset);
jjzak 6:3c54bc7badd4 26 offset += this->goal.serialize(outbuffer + offset);
jjzak 6:3c54bc7badd4 27 union {
jjzak 6:3c54bc7badd4 28 float real;
jjzak 6:3c54bc7badd4 29 uint32_t base;
jjzak 6:3c54bc7badd4 30 } u_tolerance;
jjzak 6:3c54bc7badd4 31 u_tolerance.real = this->tolerance;
jjzak 6:3c54bc7badd4 32 *(outbuffer + offset + 0) = (u_tolerance.base >> (8 * 0)) & 0xFF;
jjzak 6:3c54bc7badd4 33 *(outbuffer + offset + 1) = (u_tolerance.base >> (8 * 1)) & 0xFF;
jjzak 6:3c54bc7badd4 34 *(outbuffer + offset + 2) = (u_tolerance.base >> (8 * 2)) & 0xFF;
jjzak 6:3c54bc7badd4 35 *(outbuffer + offset + 3) = (u_tolerance.base >> (8 * 3)) & 0xFF;
jjzak 6:3c54bc7badd4 36 offset += sizeof(this->tolerance);
jjzak 6:3c54bc7badd4 37 return offset;
jjzak 6:3c54bc7badd4 38 }
jjzak 6:3c54bc7badd4 39
jjzak 6:3c54bc7badd4 40 virtual int deserialize(unsigned char *inbuffer)
jjzak 6:3c54bc7badd4 41 {
jjzak 6:3c54bc7badd4 42 int offset = 0;
jjzak 6:3c54bc7badd4 43 offset += this->start.deserialize(inbuffer + offset);
jjzak 6:3c54bc7badd4 44 offset += this->goal.deserialize(inbuffer + offset);
jjzak 6:3c54bc7badd4 45 union {
jjzak 6:3c54bc7badd4 46 float real;
jjzak 6:3c54bc7badd4 47 uint32_t base;
jjzak 6:3c54bc7badd4 48 } u_tolerance;
jjzak 6:3c54bc7badd4 49 u_tolerance.base = 0;
jjzak 6:3c54bc7badd4 50 u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
jjzak 6:3c54bc7badd4 51 u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
jjzak 6:3c54bc7badd4 52 u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
jjzak 6:3c54bc7badd4 53 u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
jjzak 6:3c54bc7badd4 54 this->tolerance = u_tolerance.real;
jjzak 6:3c54bc7badd4 55 offset += sizeof(this->tolerance);
jjzak 6:3c54bc7badd4 56 return offset;
jjzak 6:3c54bc7badd4 57 }
jjzak 6:3c54bc7badd4 58
jjzak 6:3c54bc7badd4 59 const char * getType(){ return GETPLAN; };
jjzak 6:3c54bc7badd4 60 const char * getMD5(){ return "e25a43e0752bcca599a8c2eef8282df8"; };
jjzak 6:3c54bc7badd4 61
jjzak 6:3c54bc7badd4 62 };
jjzak 6:3c54bc7badd4 63
jjzak 6:3c54bc7badd4 64 class GetPlanResponse : public ros::Msg
jjzak 6:3c54bc7badd4 65 {
jjzak 6:3c54bc7badd4 66 public:
jjzak 6:3c54bc7badd4 67 nav_msgs::Path plan;
jjzak 6:3c54bc7badd4 68
jjzak 6:3c54bc7badd4 69 virtual int serialize(unsigned char *outbuffer) const
jjzak 6:3c54bc7badd4 70 {
jjzak 6:3c54bc7badd4 71 int offset = 0;
jjzak 6:3c54bc7badd4 72 offset += this->plan.serialize(outbuffer + offset);
jjzak 6:3c54bc7badd4 73 return offset;
jjzak 6:3c54bc7badd4 74 }
jjzak 6:3c54bc7badd4 75
jjzak 6:3c54bc7badd4 76 virtual int deserialize(unsigned char *inbuffer)
jjzak 6:3c54bc7badd4 77 {
jjzak 6:3c54bc7badd4 78 int offset = 0;
jjzak 6:3c54bc7badd4 79 offset += this->plan.deserialize(inbuffer + offset);
jjzak 6:3c54bc7badd4 80 return offset;
jjzak 6:3c54bc7badd4 81 }
jjzak 6:3c54bc7badd4 82
jjzak 6:3c54bc7badd4 83 const char * getType(){ return GETPLAN; };
jjzak 6:3c54bc7badd4 84 const char * getMD5(){ return "0002bc113c0259d71f6cf8cbc9430e18"; };
jjzak 6:3c54bc7badd4 85
jjzak 6:3c54bc7badd4 86 };
jjzak 6:3c54bc7badd4 87
jjzak 6:3c54bc7badd4 88 class GetPlan {
jjzak 6:3c54bc7badd4 89 public:
jjzak 6:3c54bc7badd4 90 typedef GetPlanRequest Request;
jjzak 6:3c54bc7badd4 91 typedef GetPlanResponse Response;
jjzak 6:3c54bc7badd4 92 };
jjzak 6:3c54bc7badd4 93
jjzak 6:3c54bc7badd4 94 }
jjzak 6:3c54bc7badd4 95 #endif
jjzak 6:3c54bc7badd4 96