hairo

Dependencies:   mbed BufferedSerial

Revision:
0:9e9b7db60fd5
diff -r 000000000000 -r 9e9b7db60fd5 nav_msgs/SetMap.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/SetMap.h	Sat Dec 31 00:48:34 2016 +0000
@@ -0,0 +1,100 @@
+#ifndef _ROS_SERVICE_SetMap_h
+#define _ROS_SERVICE_SetMap_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "nav_msgs/OccupancyGrid.h"
+#include "geometry_msgs/PoseWithCovarianceStamped.h"
+
+namespace nav_msgs
+{
+
+static const char SETMAP[] = "nav_msgs/SetMap";
+
+  class SetMapRequest : public ros::Msg
+  {
+    public:
+      typedef nav_msgs::OccupancyGrid _map_type;
+      _map_type map;
+      typedef geometry_msgs::PoseWithCovarianceStamped _initial_pose_type;
+      _initial_pose_type initial_pose;
+
+    SetMapRequest():
+      map(),
+      initial_pose()
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->map.serialize(outbuffer + offset);
+      offset += this->initial_pose.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->map.deserialize(inbuffer + offset);
+      offset += this->initial_pose.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    const char * getType(){ return SETMAP; };
+    const char * getMD5(){ return "91149a20d7be299b87c340df8cc94fd4"; };
+
+  };
+
+  class SetMapResponse : public ros::Msg
+  {
+    public:
+      typedef bool _success_type;
+      _success_type success;
+
+    SetMapResponse():
+      success(0)
+    {
+    }
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.real = this->success;
+      *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->success);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_success;
+      u_success.base = 0;
+      u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->success = u_success.real;
+      offset += sizeof(this->success);
+     return offset;
+    }
+
+    const char * getType(){ return SETMAP; };
+    const char * getMD5(){ return "358e233cde0c8a8bcfea4ce193f8fc15"; };
+
+  };
+
+  class SetMap {
+    public:
+    typedef SetMapRequest Request;
+    typedef SetMapResponse Response;
+  };
+
+}
+#endif