ROS Serial library for Mbed platforms for ROS Melodic Morenia. Check http://wiki.ros.org/rosserial_mbed/ for more information.
Dependents: rosserial_mbed_hello_world_publisher_melodic Motortest Nucleo_vr_servo_project NucleoFM ... more
TwoIntsGoal.h
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 typedef int64_t _a_type; 00016 _a_type a; 00017 typedef int64_t _b_type; 00018 _b_type b; 00019 00020 TwoIntsGoal(): 00021 a(0), 00022 b(0) 00023 { 00024 } 00025 00026 virtual int serialize(unsigned char *outbuffer) const 00027 { 00028 int offset = 0; 00029 union { 00030 int64_t real; 00031 uint64_t base; 00032 } u_a; 00033 u_a.real = this->a; 00034 *(outbuffer + offset + 0) = (u_a.base >> (8 * 0)) & 0xFF; 00035 *(outbuffer + offset + 1) = (u_a.base >> (8 * 1)) & 0xFF; 00036 *(outbuffer + offset + 2) = (u_a.base >> (8 * 2)) & 0xFF; 00037 *(outbuffer + offset + 3) = (u_a.base >> (8 * 3)) & 0xFF; 00038 *(outbuffer + offset + 4) = (u_a.base >> (8 * 4)) & 0xFF; 00039 *(outbuffer + offset + 5) = (u_a.base >> (8 * 5)) & 0xFF; 00040 *(outbuffer + offset + 6) = (u_a.base >> (8 * 6)) & 0xFF; 00041 *(outbuffer + offset + 7) = (u_a.base >> (8 * 7)) & 0xFF; 00042 offset += sizeof(this->a); 00043 union { 00044 int64_t real; 00045 uint64_t base; 00046 } u_b; 00047 u_b.real = this->b; 00048 *(outbuffer + offset + 0) = (u_b.base >> (8 * 0)) & 0xFF; 00049 *(outbuffer + offset + 1) = (u_b.base >> (8 * 1)) & 0xFF; 00050 *(outbuffer + offset + 2) = (u_b.base >> (8 * 2)) & 0xFF; 00051 *(outbuffer + offset + 3) = (u_b.base >> (8 * 3)) & 0xFF; 00052 *(outbuffer + offset + 4) = (u_b.base >> (8 * 4)) & 0xFF; 00053 *(outbuffer + offset + 5) = (u_b.base >> (8 * 5)) & 0xFF; 00054 *(outbuffer + offset + 6) = (u_b.base >> (8 * 6)) & 0xFF; 00055 *(outbuffer + offset + 7) = (u_b.base >> (8 * 7)) & 0xFF; 00056 offset += sizeof(this->b); 00057 return offset; 00058 } 00059 00060 virtual int deserialize(unsigned char *inbuffer) 00061 { 00062 int offset = 0; 00063 union { 00064 int64_t real; 00065 uint64_t base; 00066 } u_a; 00067 u_a.base = 0; 00068 u_a.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); 00069 u_a.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); 00070 u_a.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); 00071 u_a.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); 00072 u_a.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); 00073 u_a.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); 00074 u_a.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); 00075 u_a.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); 00076 this->a = u_a.real; 00077 offset += sizeof(this->a); 00078 union { 00079 int64_t real; 00080 uint64_t base; 00081 } u_b; 00082 u_b.base = 0; 00083 u_b.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); 00084 u_b.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); 00085 u_b.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); 00086 u_b.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); 00087 u_b.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); 00088 u_b.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); 00089 u_b.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); 00090 u_b.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); 00091 this->b = u_b.real; 00092 offset += sizeof(this->b); 00093 return offset; 00094 } 00095 00096 const char * getType(){ return "actionlib/TwoIntsGoal"; }; 00097 const char * getMD5(){ return "36d09b846be0b371c5f190354dd3153e"; }; 00098 00099 }; 00100 00101 } 00102 #endif
Generated on Tue Jul 12 2022 13:50:06 by 1.7.2