Working towards recieving twists

Dependencies:   BufferedSerial

Fork of ros_lib_kinetic by Gary Servin

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers AssembleScans2.h Source File

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       typedef ros::Time _begin_type;
00019       _begin_type begin;
00020       typedef ros::Time _end_type;
00021       _end_type end;
00022 
00023     AssembleScans2Request():
00024       begin(),
00025       end()
00026     {
00027     }
00028 
00029     virtual int serialize(unsigned char *outbuffer) const
00030     {
00031       int offset = 0;
00032       *(outbuffer + offset + 0) = (this->begin.sec >> (8 * 0)) & 0xFF;
00033       *(outbuffer + offset + 1) = (this->begin.sec >> (8 * 1)) & 0xFF;
00034       *(outbuffer + offset + 2) = (this->begin.sec >> (8 * 2)) & 0xFF;
00035       *(outbuffer + offset + 3) = (this->begin.sec >> (8 * 3)) & 0xFF;
00036       offset += sizeof(this->begin.sec);
00037       *(outbuffer + offset + 0) = (this->begin.nsec >> (8 * 0)) & 0xFF;
00038       *(outbuffer + offset + 1) = (this->begin.nsec >> (8 * 1)) & 0xFF;
00039       *(outbuffer + offset + 2) = (this->begin.nsec >> (8 * 2)) & 0xFF;
00040       *(outbuffer + offset + 3) = (this->begin.nsec >> (8 * 3)) & 0xFF;
00041       offset += sizeof(this->begin.nsec);
00042       *(outbuffer + offset + 0) = (this->end.sec >> (8 * 0)) & 0xFF;
00043       *(outbuffer + offset + 1) = (this->end.sec >> (8 * 1)) & 0xFF;
00044       *(outbuffer + offset + 2) = (this->end.sec >> (8 * 2)) & 0xFF;
00045       *(outbuffer + offset + 3) = (this->end.sec >> (8 * 3)) & 0xFF;
00046       offset += sizeof(this->end.sec);
00047       *(outbuffer + offset + 0) = (this->end.nsec >> (8 * 0)) & 0xFF;
00048       *(outbuffer + offset + 1) = (this->end.nsec >> (8 * 1)) & 0xFF;
00049       *(outbuffer + offset + 2) = (this->end.nsec >> (8 * 2)) & 0xFF;
00050       *(outbuffer + offset + 3) = (this->end.nsec >> (8 * 3)) & 0xFF;
00051       offset += sizeof(this->end.nsec);
00052       return offset;
00053     }
00054 
00055     virtual int deserialize(unsigned char *inbuffer)
00056     {
00057       int offset = 0;
00058       this->begin.sec =  ((uint32_t) (*(inbuffer + offset)));
00059       this->begin.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00060       this->begin.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00061       this->begin.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00062       offset += sizeof(this->begin.sec);
00063       this->begin.nsec =  ((uint32_t) (*(inbuffer + offset)));
00064       this->begin.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00065       this->begin.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00066       this->begin.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00067       offset += sizeof(this->begin.nsec);
00068       this->end.sec =  ((uint32_t) (*(inbuffer + offset)));
00069       this->end.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00070       this->end.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00071       this->end.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00072       offset += sizeof(this->end.sec);
00073       this->end.nsec =  ((uint32_t) (*(inbuffer + offset)));
00074       this->end.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00075       this->end.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00076       this->end.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00077       offset += sizeof(this->end.nsec);
00078      return offset;
00079     }
00080 
00081     const char * getType(){ return ASSEMBLESCANS2; };
00082     const char * getMD5(){ return "b341004f74e15bf5e1b2053a9183bdc7"; };
00083 
00084   };
00085 
00086   class AssembleScans2Response : public ros::Msg
00087   {
00088     public:
00089       typedef sensor_msgs::PointCloud2 _cloud_type;
00090       _cloud_type cloud;
00091 
00092     AssembleScans2Response():
00093       cloud()
00094     {
00095     }
00096 
00097     virtual int serialize(unsigned char *outbuffer) const
00098     {
00099       int offset = 0;
00100       offset += this->cloud.serialize(outbuffer + offset);
00101       return offset;
00102     }
00103 
00104     virtual int deserialize(unsigned char *inbuffer)
00105     {
00106       int offset = 0;
00107       offset += this->cloud.deserialize(inbuffer + offset);
00108      return offset;
00109     }
00110 
00111     const char * getType(){ return ASSEMBLESCANS2; };
00112     const char * getMD5(){ return "96cec5374164b3b3d1d7ef5d7628a7ed"; };
00113 
00114   };
00115 
00116   class AssembleScans2 {
00117     public:
00118     typedef AssembleScans2Request Request;
00119     typedef AssembleScans2Response Response;
00120   };
00121 
00122 }
00123 #endif