added 1 custom message

Dependencies:   BufferedSerial

Fork of ros_lib_kinetic by Gary Servin

Committer:
randalthor
Date:
Fri May 19 08:59:12 2017 +0000
Revision:
2:af816ffd33df
Parent:
0:9e9b7db60fd5
custom message mobile robot added for ITU cyber physical lab

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:9e9b7db60fd5 1 #ifndef _ROS_SERVICE_AssembleScans_h
garyservin 0:9e9b7db60fd5 2 #define _ROS_SERVICE_AssembleScans_h
garyservin 0:9e9b7db60fd5 3 #include <stdint.h>
garyservin 0:9e9b7db60fd5 4 #include <string.h>
garyservin 0:9e9b7db60fd5 5 #include <stdlib.h>
garyservin 0:9e9b7db60fd5 6 #include "ros/msg.h"
garyservin 0:9e9b7db60fd5 7 #include "ros/time.h"
garyservin 0:9e9b7db60fd5 8 #include "sensor_msgs/PointCloud.h"
garyservin 0:9e9b7db60fd5 9
garyservin 0:9e9b7db60fd5 10 namespace laser_assembler
garyservin 0:9e9b7db60fd5 11 {
garyservin 0:9e9b7db60fd5 12
garyservin 0:9e9b7db60fd5 13 static const char ASSEMBLESCANS[] = "laser_assembler/AssembleScans";
garyservin 0:9e9b7db60fd5 14
garyservin 0:9e9b7db60fd5 15 class AssembleScansRequest : public ros::Msg
garyservin 0:9e9b7db60fd5 16 {
garyservin 0:9e9b7db60fd5 17 public:
garyservin 0:9e9b7db60fd5 18 typedef ros::Time _begin_type;
garyservin 0:9e9b7db60fd5 19 _begin_type begin;
garyservin 0:9e9b7db60fd5 20 typedef ros::Time _end_type;
garyservin 0:9e9b7db60fd5 21 _end_type end;
garyservin 0:9e9b7db60fd5 22
garyservin 0:9e9b7db60fd5 23 AssembleScansRequest():
garyservin 0:9e9b7db60fd5 24 begin(),
garyservin 0:9e9b7db60fd5 25 end()
garyservin 0:9e9b7db60fd5 26 {
garyservin 0:9e9b7db60fd5 27 }
garyservin 0:9e9b7db60fd5 28
garyservin 0:9e9b7db60fd5 29 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:9e9b7db60fd5 30 {
garyservin 0:9e9b7db60fd5 31 int offset = 0;
garyservin 0:9e9b7db60fd5 32 *(outbuffer + offset + 0) = (this->begin.sec >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 33 *(outbuffer + offset + 1) = (this->begin.sec >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 34 *(outbuffer + offset + 2) = (this->begin.sec >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 35 *(outbuffer + offset + 3) = (this->begin.sec >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 36 offset += sizeof(this->begin.sec);
garyservin 0:9e9b7db60fd5 37 *(outbuffer + offset + 0) = (this->begin.nsec >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 38 *(outbuffer + offset + 1) = (this->begin.nsec >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 39 *(outbuffer + offset + 2) = (this->begin.nsec >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 40 *(outbuffer + offset + 3) = (this->begin.nsec >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 41 offset += sizeof(this->begin.nsec);
garyservin 0:9e9b7db60fd5 42 *(outbuffer + offset + 0) = (this->end.sec >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 43 *(outbuffer + offset + 1) = (this->end.sec >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 44 *(outbuffer + offset + 2) = (this->end.sec >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 45 *(outbuffer + offset + 3) = (this->end.sec >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 46 offset += sizeof(this->end.sec);
garyservin 0:9e9b7db60fd5 47 *(outbuffer + offset + 0) = (this->end.nsec >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 48 *(outbuffer + offset + 1) = (this->end.nsec >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 49 *(outbuffer + offset + 2) = (this->end.nsec >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 50 *(outbuffer + offset + 3) = (this->end.nsec >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 51 offset += sizeof(this->end.nsec);
garyservin 0:9e9b7db60fd5 52 return offset;
garyservin 0:9e9b7db60fd5 53 }
garyservin 0:9e9b7db60fd5 54
garyservin 0:9e9b7db60fd5 55 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:9e9b7db60fd5 56 {
garyservin 0:9e9b7db60fd5 57 int offset = 0;
garyservin 0:9e9b7db60fd5 58 this->begin.sec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 59 this->begin.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 60 this->begin.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 61 this->begin.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 62 offset += sizeof(this->begin.sec);
garyservin 0:9e9b7db60fd5 63 this->begin.nsec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 64 this->begin.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 65 this->begin.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 66 this->begin.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 67 offset += sizeof(this->begin.nsec);
garyservin 0:9e9b7db60fd5 68 this->end.sec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 69 this->end.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 70 this->end.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 71 this->end.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 72 offset += sizeof(this->end.sec);
garyservin 0:9e9b7db60fd5 73 this->end.nsec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 74 this->end.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 75 this->end.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 76 this->end.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 77 offset += sizeof(this->end.nsec);
garyservin 0:9e9b7db60fd5 78 return offset;
garyservin 0:9e9b7db60fd5 79 }
garyservin 0:9e9b7db60fd5 80
garyservin 0:9e9b7db60fd5 81 const char * getType(){ return ASSEMBLESCANS; };
garyservin 0:9e9b7db60fd5 82 const char * getMD5(){ return "b341004f74e15bf5e1b2053a9183bdc7"; };
garyservin 0:9e9b7db60fd5 83
garyservin 0:9e9b7db60fd5 84 };
garyservin 0:9e9b7db60fd5 85
garyservin 0:9e9b7db60fd5 86 class AssembleScansResponse : public ros::Msg
garyservin 0:9e9b7db60fd5 87 {
garyservin 0:9e9b7db60fd5 88 public:
garyservin 0:9e9b7db60fd5 89 typedef sensor_msgs::PointCloud _cloud_type;
garyservin 0:9e9b7db60fd5 90 _cloud_type cloud;
garyservin 0:9e9b7db60fd5 91
garyservin 0:9e9b7db60fd5 92 AssembleScansResponse():
garyservin 0:9e9b7db60fd5 93 cloud()
garyservin 0:9e9b7db60fd5 94 {
garyservin 0:9e9b7db60fd5 95 }
garyservin 0:9e9b7db60fd5 96
garyservin 0:9e9b7db60fd5 97 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:9e9b7db60fd5 98 {
garyservin 0:9e9b7db60fd5 99 int offset = 0;
garyservin 0:9e9b7db60fd5 100 offset += this->cloud.serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 101 return offset;
garyservin 0:9e9b7db60fd5 102 }
garyservin 0:9e9b7db60fd5 103
garyservin 0:9e9b7db60fd5 104 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:9e9b7db60fd5 105 {
garyservin 0:9e9b7db60fd5 106 int offset = 0;
garyservin 0:9e9b7db60fd5 107 offset += this->cloud.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 108 return offset;
garyservin 0:9e9b7db60fd5 109 }
garyservin 0:9e9b7db60fd5 110
garyservin 0:9e9b7db60fd5 111 const char * getType(){ return ASSEMBLESCANS; };
garyservin 0:9e9b7db60fd5 112 const char * getMD5(){ return "4217b28a903e4ad7869a83b3653110ff"; };
garyservin 0:9e9b7db60fd5 113
garyservin 0:9e9b7db60fd5 114 };
garyservin 0:9e9b7db60fd5 115
garyservin 0:9e9b7db60fd5 116 class AssembleScans {
garyservin 0:9e9b7db60fd5 117 public:
garyservin 0:9e9b7db60fd5 118 typedef AssembleScansRequest Request;
garyservin 0:9e9b7db60fd5 119 typedef AssembleScansResponse Response;
garyservin 0:9e9b7db60fd5 120 };
garyservin 0:9e9b7db60fd5 121
garyservin 0:9e9b7db60fd5 122 }
garyservin 0:9e9b7db60fd5 123 #endif