Go to the documentation of this file.00001 #ifndef _ROS_SERVICE_AssembleScans_h
00002 #define _ROS_SERVICE_AssembleScans_h
00003 #include <stdint.h>
00004 #include <string.h>
00005 #include <stdlib.h>
00006 #include "ros/msg.h"
00007 #include "ros/time.h"
00008 #include "sensor_msgs/PointCloud.h"
00009
00010 namespace laser_assembler
00011 {
00012
00013 static const char ASSEMBLESCANS[] = "laser_assembler/AssembleScans";
00014
00015 class AssembleScansRequest : public ros::Msg
00016 {
00017 public:
00018 ros::Time begin;
00019 ros::Time end;
00020
00021 virtual int serialize(unsigned char *outbuffer) const
00022 {
00023 int offset = 0;
00024 *(outbuffer + offset + 0) = (this->begin.sec >> (8 * 0)) & 0xFF;
00025 *(outbuffer + offset + 1) = (this->begin.sec >> (8 * 1)) & 0xFF;
00026 *(outbuffer + offset + 2) = (this->begin.sec >> (8 * 2)) & 0xFF;
00027 *(outbuffer + offset + 3) = (this->begin.sec >> (8 * 3)) & 0xFF;
00028 offset += sizeof(this->begin.sec);
00029 *(outbuffer + offset + 0) = (this->begin.nsec >> (8 * 0)) & 0xFF;
00030 *(outbuffer + offset + 1) = (this->begin.nsec >> (8 * 1)) & 0xFF;
00031 *(outbuffer + offset + 2) = (this->begin.nsec >> (8 * 2)) & 0xFF;
00032 *(outbuffer + offset + 3) = (this->begin.nsec >> (8 * 3)) & 0xFF;
00033 offset += sizeof(this->begin.nsec);
00034 *(outbuffer + offset + 0) = (this->end.sec >> (8 * 0)) & 0xFF;
00035 *(outbuffer + offset + 1) = (this->end.sec >> (8 * 1)) & 0xFF;
00036 *(outbuffer + offset + 2) = (this->end.sec >> (8 * 2)) & 0xFF;
00037 *(outbuffer + offset + 3) = (this->end.sec >> (8 * 3)) & 0xFF;
00038 offset += sizeof(this->end.sec);
00039 *(outbuffer + offset + 0) = (this->end.nsec >> (8 * 0)) & 0xFF;
00040 *(outbuffer + offset + 1) = (this->end.nsec >> (8 * 1)) & 0xFF;
00041 *(outbuffer + offset + 2) = (this->end.nsec >> (8 * 2)) & 0xFF;
00042 *(outbuffer + offset + 3) = (this->end.nsec >> (8 * 3)) & 0xFF;
00043 offset += sizeof(this->end.nsec);
00044 return offset;
00045 }
00046
00047 virtual int deserialize(unsigned char *inbuffer)
00048 {
00049 int offset = 0;
00050 this->begin.sec = ((uint32_t) (*(inbuffer + offset)));
00051 this->begin.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00052 this->begin.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00053 this->begin.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00054 offset += sizeof(this->begin.sec);
00055 this->begin.nsec = ((uint32_t) (*(inbuffer + offset)));
00056 this->begin.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00057 this->begin.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00058 this->begin.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00059 offset += sizeof(this->begin.nsec);
00060 this->end.sec = ((uint32_t) (*(inbuffer + offset)));
00061 this->end.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00062 this->end.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00063 this->end.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00064 offset += sizeof(this->end.sec);
00065 this->end.nsec = ((uint32_t) (*(inbuffer + offset)));
00066 this->end.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00067 this->end.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00068 this->end.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00069 offset += sizeof(this->end.nsec);
00070 return offset;
00071 }
00072
00073 const char * getType(){ return ASSEMBLESCANS; };
00074 const char * getMD5(){ return "b341004f74e15bf5e1b2053a9183bdc7"; };
00075
00076 };
00077
00078 class AssembleScansResponse : public ros::Msg
00079 {
00080 public:
00081 sensor_msgs::PointCloud cloud;
00082
00083 virtual int serialize(unsigned char *outbuffer) const
00084 {
00085 int offset = 0;
00086 offset += this->cloud.serialize(outbuffer + offset);
00087 return offset;
00088 }
00089
00090 virtual int deserialize(unsigned char *inbuffer)
00091 {
00092 int offset = 0;
00093 offset += this->cloud.deserialize(inbuffer + offset);
00094 return offset;
00095 }
00096
00097 const char * getType(){ return ASSEMBLESCANS; };
00098 const char * getMD5(){ return "4217b28a903e4ad7869a83b3653110ff"; };
00099
00100 };
00101
00102 class AssembleScans {
00103 public:
00104 typedef AssembleScansRequest Request;
00105 typedef AssembleScansResponse Response;
00106 };
00107
00108 }
00109 #endif