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

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher rtos_base_control rosserial_mbed_F64MA ROS-RTOS ... more

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers SetMap.h Source File

SetMap.h

00001 #ifndef _ROS_SERVICE_SetMap_h
00002 #define _ROS_SERVICE_SetMap_h
00003 #include <stdint.h>
00004 #include <string.h>
00005 #include <stdlib.h>
00006 #include "ros/msg.h"
00007 #include "nav_msgs/OccupancyGrid.h"
00008 #include "geometry_msgs/PoseWithCovarianceStamped.h"
00009 
00010 namespace nav_msgs
00011 {
00012 
00013 static const char SETMAP[] = "nav_msgs/SetMap";
00014 
00015   class SetMapRequest : public ros::Msg
00016   {
00017     public:
00018       nav_msgs::OccupancyGrid map;
00019       geometry_msgs::PoseWithCovarianceStamped initial_pose;
00020 
00021     SetMapRequest():
00022       map(),
00023       initial_pose()
00024     {
00025     }
00026 
00027     virtual int serialize(unsigned char *outbuffer) const
00028     {
00029       int offset = 0;
00030       offset += this->map.serialize(outbuffer + offset);
00031       offset += this->initial_pose.serialize(outbuffer + offset);
00032       return offset;
00033     }
00034 
00035     virtual int deserialize(unsigned char *inbuffer)
00036     {
00037       int offset = 0;
00038       offset += this->map.deserialize(inbuffer + offset);
00039       offset += this->initial_pose.deserialize(inbuffer + offset);
00040      return offset;
00041     }
00042 
00043     const char * getType(){ return SETMAP; };
00044     const char * getMD5(){ return "91149a20d7be299b87c340df8cc94fd4"; };
00045 
00046   };
00047 
00048   class SetMapResponse : public ros::Msg
00049   {
00050     public:
00051       bool success;
00052 
00053     SetMapResponse():
00054       success(0)
00055     {
00056     }
00057 
00058     virtual int serialize(unsigned char *outbuffer) const
00059     {
00060       int offset = 0;
00061       union {
00062         bool real;
00063         uint8_t base;
00064       } u_success;
00065       u_success.real = this->success;
00066       *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
00067       offset += sizeof(this->success);
00068       return offset;
00069     }
00070 
00071     virtual int deserialize(unsigned char *inbuffer)
00072     {
00073       int offset = 0;
00074       union {
00075         bool real;
00076         uint8_t base;
00077       } u_success;
00078       u_success.base = 0;
00079       u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00080       this->success = u_success.real;
00081       offset += sizeof(this->success);
00082      return offset;
00083     }
00084 
00085     const char * getType(){ return SETMAP; };
00086     const char * getMD5(){ return "358e233cde0c8a8bcfea4ce193f8fc15"; };
00087 
00088   };
00089 
00090   class SetMap {
00091     public:
00092     typedef SetMapRequest Request;
00093     typedef SetMapResponse Response;
00094   };
00095 
00096 }
00097 #endif