ROS Serial library for Mbed platforms for ROS Indigo Igloo. Check http://wiki.ros.org/rosserial_mbed/ for more information
Dependents: rosserial_mbed_hello_world_publisher rtos_base_control rosserial_mbed_F64MA ROS-RTOS ... more
TwoInts.h
00001 #ifndef _ROS_SERVICE_TwoInts_h 00002 #define _ROS_SERVICE_TwoInts_h 00003 #include <stdint.h> 00004 #include <string.h> 00005 #include <stdlib.h> 00006 #include "ros/msg.h" 00007 00008 namespace roscpp_tutorials 00009 { 00010 00011 static const char TWOINTS[] = "roscpp_tutorials/TwoInts"; 00012 00013 class TwoIntsRequest : public ros::Msg 00014 { 00015 public: 00016 int64_t a; 00017 int64_t b; 00018 00019 TwoIntsRequest(): 00020 a(0), 00021 b(0) 00022 { 00023 } 00024 00025 virtual int serialize(unsigned char *outbuffer) const 00026 { 00027 int offset = 0; 00028 union { 00029 int64_t real; 00030 uint64_t base; 00031 } u_a; 00032 u_a.real = this->a; 00033 *(outbuffer + offset + 0) = (u_a.base >> (8 * 0)) & 0xFF; 00034 *(outbuffer + offset + 1) = (u_a.base >> (8 * 1)) & 0xFF; 00035 *(outbuffer + offset + 2) = (u_a.base >> (8 * 2)) & 0xFF; 00036 *(outbuffer + offset + 3) = (u_a.base >> (8 * 3)) & 0xFF; 00037 *(outbuffer + offset + 4) = (u_a.base >> (8 * 4)) & 0xFF; 00038 *(outbuffer + offset + 5) = (u_a.base >> (8 * 5)) & 0xFF; 00039 *(outbuffer + offset + 6) = (u_a.base >> (8 * 6)) & 0xFF; 00040 *(outbuffer + offset + 7) = (u_a.base >> (8 * 7)) & 0xFF; 00041 offset += sizeof(this->a); 00042 union { 00043 int64_t real; 00044 uint64_t base; 00045 } u_b; 00046 u_b.real = this->b; 00047 *(outbuffer + offset + 0) = (u_b.base >> (8 * 0)) & 0xFF; 00048 *(outbuffer + offset + 1) = (u_b.base >> (8 * 1)) & 0xFF; 00049 *(outbuffer + offset + 2) = (u_b.base >> (8 * 2)) & 0xFF; 00050 *(outbuffer + offset + 3) = (u_b.base >> (8 * 3)) & 0xFF; 00051 *(outbuffer + offset + 4) = (u_b.base >> (8 * 4)) & 0xFF; 00052 *(outbuffer + offset + 5) = (u_b.base >> (8 * 5)) & 0xFF; 00053 *(outbuffer + offset + 6) = (u_b.base >> (8 * 6)) & 0xFF; 00054 *(outbuffer + offset + 7) = (u_b.base >> (8 * 7)) & 0xFF; 00055 offset += sizeof(this->b); 00056 return offset; 00057 } 00058 00059 virtual int deserialize(unsigned char *inbuffer) 00060 { 00061 int offset = 0; 00062 union { 00063 int64_t real; 00064 uint64_t base; 00065 } u_a; 00066 u_a.base = 0; 00067 u_a.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); 00068 u_a.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); 00069 u_a.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); 00070 u_a.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); 00071 u_a.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); 00072 u_a.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); 00073 u_a.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); 00074 u_a.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); 00075 this->a = u_a.real; 00076 offset += sizeof(this->a); 00077 union { 00078 int64_t real; 00079 uint64_t base; 00080 } u_b; 00081 u_b.base = 0; 00082 u_b.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); 00083 u_b.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); 00084 u_b.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); 00085 u_b.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); 00086 u_b.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); 00087 u_b.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); 00088 u_b.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); 00089 u_b.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); 00090 this->b = u_b.real; 00091 offset += sizeof(this->b); 00092 return offset; 00093 } 00094 00095 const char * getType(){ return TWOINTS; }; 00096 const char * getMD5(){ return "36d09b846be0b371c5f190354dd3153e"; }; 00097 00098 }; 00099 00100 class TwoIntsResponse : public ros::Msg 00101 { 00102 public: 00103 int64_t sum; 00104 00105 TwoIntsResponse(): 00106 sum(0) 00107 { 00108 } 00109 00110 virtual int serialize(unsigned char *outbuffer) const 00111 { 00112 int offset = 0; 00113 union { 00114 int64_t real; 00115 uint64_t base; 00116 } u_sum; 00117 u_sum.real = this->sum; 00118 *(outbuffer + offset + 0) = (u_sum.base >> (8 * 0)) & 0xFF; 00119 *(outbuffer + offset + 1) = (u_sum.base >> (8 * 1)) & 0xFF; 00120 *(outbuffer + offset + 2) = (u_sum.base >> (8 * 2)) & 0xFF; 00121 *(outbuffer + offset + 3) = (u_sum.base >> (8 * 3)) & 0xFF; 00122 *(outbuffer + offset + 4) = (u_sum.base >> (8 * 4)) & 0xFF; 00123 *(outbuffer + offset + 5) = (u_sum.base >> (8 * 5)) & 0xFF; 00124 *(outbuffer + offset + 6) = (u_sum.base >> (8 * 6)) & 0xFF; 00125 *(outbuffer + offset + 7) = (u_sum.base >> (8 * 7)) & 0xFF; 00126 offset += sizeof(this->sum); 00127 return offset; 00128 } 00129 00130 virtual int deserialize(unsigned char *inbuffer) 00131 { 00132 int offset = 0; 00133 union { 00134 int64_t real; 00135 uint64_t base; 00136 } u_sum; 00137 u_sum.base = 0; 00138 u_sum.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); 00139 u_sum.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); 00140 u_sum.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); 00141 u_sum.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); 00142 u_sum.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); 00143 u_sum.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); 00144 u_sum.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); 00145 u_sum.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); 00146 this->sum = u_sum.real; 00147 offset += sizeof(this->sum); 00148 return offset; 00149 } 00150 00151 const char * getType(){ return TWOINTS; }; 00152 const char * getMD5(){ return "b88405221c77b1878a3cbbfff53428d7"; }; 00153 00154 }; 00155 00156 class TwoInts { 00157 public: 00158 typedef TwoIntsRequest Request; 00159 typedef TwoIntsResponse Response; 00160 }; 00161 00162 } 00163 #endif
Generated on Tue Jul 12 2022 18:39:41 by 1.7.2