It has only one change from original one. I added robotfeedback message on it.

Dependencies:   BufferedSerial

Dependents:   RobotFeedback mobileRobotITU

Fork of ros_lib_indigo by Gary Servin

Committer:
randalthor
Date:
Sat Mar 04 14:07:56 2017 +0000
Revision:
4:80d9bee5079a
Parent:
0:fd24f7ca9688
fatih

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:fd24f7ca9688 1 #ifndef _ROS_SERVICE_GetPointMap_h
garyservin 0:fd24f7ca9688 2 #define _ROS_SERVICE_GetPointMap_h
garyservin 0:fd24f7ca9688 3 #include <stdint.h>
garyservin 0:fd24f7ca9688 4 #include <string.h>
garyservin 0:fd24f7ca9688 5 #include <stdlib.h>
garyservin 0:fd24f7ca9688 6 #include "ros/msg.h"
garyservin 0:fd24f7ca9688 7 #include "sensor_msgs/PointCloud2.h"
garyservin 0:fd24f7ca9688 8
garyservin 0:fd24f7ca9688 9 namespace map_msgs
garyservin 0:fd24f7ca9688 10 {
garyservin 0:fd24f7ca9688 11
garyservin 0:fd24f7ca9688 12 static const char GETPOINTMAP[] = "map_msgs/GetPointMap";
garyservin 0:fd24f7ca9688 13
garyservin 0:fd24f7ca9688 14 class GetPointMapRequest : public ros::Msg
garyservin 0:fd24f7ca9688 15 {
garyservin 0:fd24f7ca9688 16 public:
garyservin 0:fd24f7ca9688 17
garyservin 0:fd24f7ca9688 18 GetPointMapRequest()
garyservin 0:fd24f7ca9688 19 {
garyservin 0:fd24f7ca9688 20 }
garyservin 0:fd24f7ca9688 21
garyservin 0:fd24f7ca9688 22 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 23 {
garyservin 0:fd24f7ca9688 24 int offset = 0;
garyservin 0:fd24f7ca9688 25 return offset;
garyservin 0:fd24f7ca9688 26 }
garyservin 0:fd24f7ca9688 27
garyservin 0:fd24f7ca9688 28 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 29 {
garyservin 0:fd24f7ca9688 30 int offset = 0;
garyservin 0:fd24f7ca9688 31 return offset;
garyservin 0:fd24f7ca9688 32 }
garyservin 0:fd24f7ca9688 33
garyservin 0:fd24f7ca9688 34 const char * getType(){ return GETPOINTMAP; };
garyservin 0:fd24f7ca9688 35 const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
garyservin 0:fd24f7ca9688 36
garyservin 0:fd24f7ca9688 37 };
garyservin 0:fd24f7ca9688 38
garyservin 0:fd24f7ca9688 39 class GetPointMapResponse : public ros::Msg
garyservin 0:fd24f7ca9688 40 {
garyservin 0:fd24f7ca9688 41 public:
garyservin 0:fd24f7ca9688 42 sensor_msgs::PointCloud2 map;
garyservin 0:fd24f7ca9688 43
garyservin 0:fd24f7ca9688 44 GetPointMapResponse():
garyservin 0:fd24f7ca9688 45 map()
garyservin 0:fd24f7ca9688 46 {
garyservin 0:fd24f7ca9688 47 }
garyservin 0:fd24f7ca9688 48
garyservin 0:fd24f7ca9688 49 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 50 {
garyservin 0:fd24f7ca9688 51 int offset = 0;
garyservin 0:fd24f7ca9688 52 offset += this->map.serialize(outbuffer + offset);
garyservin 0:fd24f7ca9688 53 return offset;
garyservin 0:fd24f7ca9688 54 }
garyservin 0:fd24f7ca9688 55
garyservin 0:fd24f7ca9688 56 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 57 {
garyservin 0:fd24f7ca9688 58 int offset = 0;
garyservin 0:fd24f7ca9688 59 offset += this->map.deserialize(inbuffer + offset);
garyservin 0:fd24f7ca9688 60 return offset;
garyservin 0:fd24f7ca9688 61 }
garyservin 0:fd24f7ca9688 62
garyservin 0:fd24f7ca9688 63 const char * getType(){ return GETPOINTMAP; };
garyservin 0:fd24f7ca9688 64 const char * getMD5(){ return "b84fbb39505086eb6a62d933c75cb7b4"; };
garyservin 0:fd24f7ca9688 65
garyservin 0:fd24f7ca9688 66 };
garyservin 0:fd24f7ca9688 67
garyservin 0:fd24f7ca9688 68 class GetPointMap {
garyservin 0:fd24f7ca9688 69 public:
garyservin 0:fd24f7ca9688 70 typedef GetPointMapRequest Request;
garyservin 0:fd24f7ca9688 71 typedef GetPointMapResponse Response;
garyservin 0:fd24f7ca9688 72 };
garyservin 0:fd24f7ca9688 73
garyservin 0:fd24f7ca9688 74 }
garyservin 0:fd24f7ca9688 75 #endif