This program is porting rosserial_arduino for mbed http://www.ros.org/wiki/rosserial_arduino This program supported the revision of 169 of rosserial. This program contains an example.

Dependencies:   rosserial_mbed_lib mbed Servo

Committer:
nucho
Date:
Sat Nov 12 23:53:04 2011 +0000
Revision:
3:dff241b66f84
Parent:
0:06fc856e99ca
This program supported the revision of 167 of rosserial.

Who changed what in which revision?

UserRevisionLine numberNew contents of line
nucho 3:dff241b66f84 1 #ifndef _ROS_SERVICE_GetMap_h
nucho 3:dff241b66f84 2 #define _ROS_SERVICE_GetMap_h
nucho 0:06fc856e99ca 3 #include <stdint.h>
nucho 0:06fc856e99ca 4 #include <string.h>
nucho 0:06fc856e99ca 5 #include <stdlib.h>
nucho 3:dff241b66f84 6 #include "ros/msg.h"
nucho 0:06fc856e99ca 7 #include "nav_msgs/OccupancyGrid.h"
nucho 0:06fc856e99ca 8
nucho 0:06fc856e99ca 9 namespace nav_msgs
nucho 0:06fc856e99ca 10 {
nucho 0:06fc856e99ca 11
nucho 0:06fc856e99ca 12 static const char GETMAP[] = "nav_msgs/GetMap";
nucho 0:06fc856e99ca 13
nucho 0:06fc856e99ca 14 class GetMapRequest : public ros::Msg
nucho 0:06fc856e99ca 15 {
nucho 0:06fc856e99ca 16 public:
nucho 0:06fc856e99ca 17
nucho 3:dff241b66f84 18 virtual int serialize(unsigned char *outbuffer) const
nucho 0:06fc856e99ca 19 {
nucho 0:06fc856e99ca 20 int offset = 0;
nucho 0:06fc856e99ca 21 return offset;
nucho 0:06fc856e99ca 22 }
nucho 0:06fc856e99ca 23
nucho 0:06fc856e99ca 24 virtual int deserialize(unsigned char *inbuffer)
nucho 0:06fc856e99ca 25 {
nucho 0:06fc856e99ca 26 int offset = 0;
nucho 0:06fc856e99ca 27 return offset;
nucho 0:06fc856e99ca 28 }
nucho 0:06fc856e99ca 29
nucho 3:dff241b66f84 30 virtual const char * getType(){ return GETMAP; };
nucho 3:dff241b66f84 31 virtual const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
nucho 0:06fc856e99ca 32
nucho 0:06fc856e99ca 33 };
nucho 0:06fc856e99ca 34
nucho 0:06fc856e99ca 35 class GetMapResponse : public ros::Msg
nucho 0:06fc856e99ca 36 {
nucho 0:06fc856e99ca 37 public:
nucho 0:06fc856e99ca 38 nav_msgs::OccupancyGrid map;
nucho 0:06fc856e99ca 39
nucho 3:dff241b66f84 40 virtual int serialize(unsigned char *outbuffer) const
nucho 0:06fc856e99ca 41 {
nucho 0:06fc856e99ca 42 int offset = 0;
nucho 0:06fc856e99ca 43 offset += this->map.serialize(outbuffer + offset);
nucho 0:06fc856e99ca 44 return offset;
nucho 0:06fc856e99ca 45 }
nucho 0:06fc856e99ca 46
nucho 0:06fc856e99ca 47 virtual int deserialize(unsigned char *inbuffer)
nucho 0:06fc856e99ca 48 {
nucho 0:06fc856e99ca 49 int offset = 0;
nucho 0:06fc856e99ca 50 offset += this->map.deserialize(inbuffer + offset);
nucho 0:06fc856e99ca 51 return offset;
nucho 0:06fc856e99ca 52 }
nucho 0:06fc856e99ca 53
nucho 3:dff241b66f84 54 virtual const char * getType(){ return GETMAP; };
nucho 3:dff241b66f84 55 virtual const char * getMD5(){ return "6cdd0a18e0aff5b0a3ca2326a89b54ff"; };
nucho 3:dff241b66f84 56
nucho 3:dff241b66f84 57 };
nucho 0:06fc856e99ca 58
nucho 3:dff241b66f84 59 class GetMap {
nucho 3:dff241b66f84 60 public:
nucho 3:dff241b66f84 61 typedef GetMapRequest Request;
nucho 3:dff241b66f84 62 typedef GetMapResponse Response;
nucho 0:06fc856e99ca 63 };
nucho 0:06fc856e99ca 64
nucho 0:06fc856e99ca 65 }
nucho 0:06fc856e99ca 66 #endif