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
Diff: nav_msgs/GetMap.h
- Revision:
- 3:dff241b66f84
- Parent:
- 0:06fc856e99ca
diff -r 094e5153a559 -r dff241b66f84 nav_msgs/GetMap.h --- a/nav_msgs/GetMap.h Sun Oct 16 09:33:53 2011 +0000 +++ b/nav_msgs/GetMap.h Sat Nov 12 23:53:04 2011 +0000 @@ -1,9 +1,9 @@ -#ifndef ros_SERVICE_GetMap_h -#define ros_SERVICE_GetMap_h +#ifndef _ROS_SERVICE_GetMap_h +#define _ROS_SERVICE_GetMap_h #include <stdint.h> #include <string.h> #include <stdlib.h> -#include "../ros/msg.h" +#include "ros/msg.h" #include "nav_msgs/OccupancyGrid.h" namespace nav_msgs @@ -15,7 +15,7 @@ { public: - virtual int serialize(unsigned char *outbuffer) + virtual int serialize(unsigned char *outbuffer) const { int offset = 0; return offset; @@ -27,7 +27,8 @@ return offset; } - const char * getType(){ return GETMAP; }; + virtual const char * getType(){ return GETMAP; }; + virtual const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; }; @@ -36,7 +37,7 @@ public: nav_msgs::OccupancyGrid map; - virtual int serialize(unsigned char *outbuffer) + virtual int serialize(unsigned char *outbuffer) const { int offset = 0; offset += this->map.serialize(outbuffer + offset); @@ -50,8 +51,15 @@ return offset; } - virtual const char * getType(){ return GETMAP; }; + virtual const char * getType(){ return GETMAP; }; + virtual const char * getMD5(){ return "6cdd0a18e0aff5b0a3ca2326a89b54ff"; }; + + }; + class GetMap { + public: + typedef GetMapRequest Request; + typedef GetMapResponse Response; }; }