Go to the documentation of this file.00001 #ifndef _ROS_actionlib_TwoIntsGoal_h
00002 #define _ROS_actionlib_TwoIntsGoal_h
00003
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008
00009 namespace actionlib
00010 {
00011
00012 class TwoIntsGoal : public ros::Msg
00013 {
00014 public:
00015 int64_t a;
00016 int64_t b;
00017
00018 virtual int serialize(unsigned char *outbuffer) const
00019 {
00020 int offset = 0;
00021 union {
00022 int64_t real;
00023 uint64_t base;
00024 } u_a;
00025 u_a.real = this->a;
00026 *(outbuffer + offset + 0) = (u_a.base >> (8 * 0)) & 0xFF;
00027 *(outbuffer + offset + 1) = (u_a.base >> (8 * 1)) & 0xFF;
00028 *(outbuffer + offset + 2) = (u_a.base >> (8 * 2)) & 0xFF;
00029 *(outbuffer + offset + 3) = (u_a.base >> (8 * 3)) & 0xFF;
00030 *(outbuffer + offset + 4) = (u_a.base >> (8 * 4)) & 0xFF;
00031 *(outbuffer + offset + 5) = (u_a.base >> (8 * 5)) & 0xFF;
00032 *(outbuffer + offset + 6) = (u_a.base >> (8 * 6)) & 0xFF;
00033 *(outbuffer + offset + 7) = (u_a.base >> (8 * 7)) & 0xFF;
00034 offset += sizeof(this->a);
00035 union {
00036 int64_t real;
00037 uint64_t base;
00038 } u_b;
00039 u_b.real = this->b;
00040 *(outbuffer + offset + 0) = (u_b.base >> (8 * 0)) & 0xFF;
00041 *(outbuffer + offset + 1) = (u_b.base >> (8 * 1)) & 0xFF;
00042 *(outbuffer + offset + 2) = (u_b.base >> (8 * 2)) & 0xFF;
00043 *(outbuffer + offset + 3) = (u_b.base >> (8 * 3)) & 0xFF;
00044 *(outbuffer + offset + 4) = (u_b.base >> (8 * 4)) & 0xFF;
00045 *(outbuffer + offset + 5) = (u_b.base >> (8 * 5)) & 0xFF;
00046 *(outbuffer + offset + 6) = (u_b.base >> (8 * 6)) & 0xFF;
00047 *(outbuffer + offset + 7) = (u_b.base >> (8 * 7)) & 0xFF;
00048 offset += sizeof(this->b);
00049 return offset;
00050 }
00051
00052 virtual int deserialize(unsigned char *inbuffer)
00053 {
00054 int offset = 0;
00055 union {
00056 int64_t real;
00057 uint64_t base;
00058 } u_a;
00059 u_a.base = 0;
00060 u_a.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
00061 u_a.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
00062 u_a.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
00063 u_a.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
00064 u_a.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
00065 u_a.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
00066 u_a.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
00067 u_a.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
00068 this->a = u_a.real;
00069 offset += sizeof(this->a);
00070 union {
00071 int64_t real;
00072 uint64_t base;
00073 } u_b;
00074 u_b.base = 0;
00075 u_b.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
00076 u_b.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
00077 u_b.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
00078 u_b.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
00079 u_b.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
00080 u_b.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
00081 u_b.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
00082 u_b.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
00083 this->b = u_b.real;
00084 offset += sizeof(this->b);
00085 return offset;
00086 }
00087
00088 const char * getType(){ return "actionlib/TwoIntsGoal"; };
00089 const char * getMD5(){ return "36d09b846be0b371c5f190354dd3153e"; };
00090
00091 };
00092
00093 }
00094 #endif