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
AssembleScans2.h
00001 #ifndef _ROS_SERVICE_AssembleScans2_h 00002 #define _ROS_SERVICE_AssembleScans2_h 00003 #include <stdint.h> 00004 #include <string.h> 00005 #include <stdlib.h> 00006 #include "ros/msg.h" 00007 #include "sensor_msgs/PointCloud2.h" 00008 #include "ros/time.h" 00009 00010 namespace laser_assembler 00011 { 00012 00013 static const char ASSEMBLESCANS2[] = "laser_assembler/AssembleScans2"; 00014 00015 class AssembleScans2Request : public ros::Msg 00016 { 00017 public: 00018 ros::Time begin; 00019 ros::Time end; 00020 00021 AssembleScans2Request(): 00022 begin(), 00023 end() 00024 { 00025 } 00026 00027 virtual int serialize(unsigned char *outbuffer) const 00028 { 00029 int offset = 0; 00030 *(outbuffer + offset + 0) = (this->begin.sec >> (8 * 0)) & 0xFF; 00031 *(outbuffer + offset + 1) = (this->begin.sec >> (8 * 1)) & 0xFF; 00032 *(outbuffer + offset + 2) = (this->begin.sec >> (8 * 2)) & 0xFF; 00033 *(outbuffer + offset + 3) = (this->begin.sec >> (8 * 3)) & 0xFF; 00034 offset += sizeof(this->begin.sec); 00035 *(outbuffer + offset + 0) = (this->begin.nsec >> (8 * 0)) & 0xFF; 00036 *(outbuffer + offset + 1) = (this->begin.nsec >> (8 * 1)) & 0xFF; 00037 *(outbuffer + offset + 2) = (this->begin.nsec >> (8 * 2)) & 0xFF; 00038 *(outbuffer + offset + 3) = (this->begin.nsec >> (8 * 3)) & 0xFF; 00039 offset += sizeof(this->begin.nsec); 00040 *(outbuffer + offset + 0) = (this->end.sec >> (8 * 0)) & 0xFF; 00041 *(outbuffer + offset + 1) = (this->end.sec >> (8 * 1)) & 0xFF; 00042 *(outbuffer + offset + 2) = (this->end.sec >> (8 * 2)) & 0xFF; 00043 *(outbuffer + offset + 3) = (this->end.sec >> (8 * 3)) & 0xFF; 00044 offset += sizeof(this->end.sec); 00045 *(outbuffer + offset + 0) = (this->end.nsec >> (8 * 0)) & 0xFF; 00046 *(outbuffer + offset + 1) = (this->end.nsec >> (8 * 1)) & 0xFF; 00047 *(outbuffer + offset + 2) = (this->end.nsec >> (8 * 2)) & 0xFF; 00048 *(outbuffer + offset + 3) = (this->end.nsec >> (8 * 3)) & 0xFF; 00049 offset += sizeof(this->end.nsec); 00050 return offset; 00051 } 00052 00053 virtual int deserialize(unsigned char *inbuffer) 00054 { 00055 int offset = 0; 00056 this->begin.sec = ((uint32_t) (*(inbuffer + offset))); 00057 this->begin.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00058 this->begin.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00059 this->begin.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00060 offset += sizeof(this->begin.sec); 00061 this->begin.nsec = ((uint32_t) (*(inbuffer + offset))); 00062 this->begin.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00063 this->begin.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00064 this->begin.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00065 offset += sizeof(this->begin.nsec); 00066 this->end.sec = ((uint32_t) (*(inbuffer + offset))); 00067 this->end.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00068 this->end.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00069 this->end.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00070 offset += sizeof(this->end.sec); 00071 this->end.nsec = ((uint32_t) (*(inbuffer + offset))); 00072 this->end.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00073 this->end.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00074 this->end.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00075 offset += sizeof(this->end.nsec); 00076 return offset; 00077 } 00078 00079 const char * getType(){ return ASSEMBLESCANS2; }; 00080 const char * getMD5(){ return "b341004f74e15bf5e1b2053a9183bdc7"; }; 00081 00082 }; 00083 00084 class AssembleScans2Response : public ros::Msg 00085 { 00086 public: 00087 sensor_msgs::PointCloud2 cloud; 00088 00089 AssembleScans2Response(): 00090 cloud() 00091 { 00092 } 00093 00094 virtual int serialize(unsigned char *outbuffer) const 00095 { 00096 int offset = 0; 00097 offset += this->cloud.serialize(outbuffer + offset); 00098 return offset; 00099 } 00100 00101 virtual int deserialize(unsigned char *inbuffer) 00102 { 00103 int offset = 0; 00104 offset += this->cloud.deserialize(inbuffer + offset); 00105 return offset; 00106 } 00107 00108 const char * getType(){ return ASSEMBLESCANS2; }; 00109 const char * getMD5(){ return "96cec5374164b3b3d1d7ef5d7628a7ed"; }; 00110 00111 }; 00112 00113 class AssembleScans2 { 00114 public: 00115 typedef AssembleScans2Request Request; 00116 typedef AssembleScans2Response Response; 00117 }; 00118 00119 } 00120 #endif
Generated on Tue Jul 12 2022 18:39:38 by 1.7.2