ROS Serial library for Mbed platforms for ROS Kinetic Kame. Check http://wiki.ros.org/rosserial_mbed/ for more information.

Dependencies:   BufferedSerial

Dependents:   mbed-os-example-blinky

Committer:
garyservin
Date:
Sat Dec 31 00:48:34 2016 +0000
Revision:
0:9e9b7db60fd5
Initial commit, generated based on a clean kinetic-desktop-full

Who changed what in which revision?

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