Personal fork

Dependencies:   MODSERIAL

Dependents:   rosserial_mbed

Fork of rosserial_mbed_lib by nucho

Revision:
3:1cf99502f396
Parent:
1:ff0ec969dad1
--- a/nav_msgs/OccupancyGrid.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/nav_msgs/OccupancyGrid.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_nav_msgs_OccupancyGrid_h
-#define ros_nav_msgs_OccupancyGrid_h
+#ifndef _ROS_nav_msgs_OccupancyGrid_h
+#define _ROS_nav_msgs_OccupancyGrid_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "std_msgs/Header.h"
 #include "nav_msgs/MapMetaData.h"
 
@@ -16,11 +16,11 @@
     public:
       std_msgs::Header header;
       nav_msgs::MapMetaData info;
-      unsigned char data_length;
-      signed char st_data;
-      signed char * data;
+      uint8_t data_length;
+      int8_t st_data;
+      int8_t * data;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->header.serialize(outbuffer + offset);
@@ -29,10 +29,10 @@
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < data_length; i++){
+      for( uint8_t i = 0; i < data_length; i++){
       union {
-        signed char real;
-        unsigned char base;
+        int8_t real;
+        uint8_t base;
       } u_datai;
       u_datai.real = this->data[i];
       *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
@@ -46,26 +46,27 @@
       int offset = 0;
       offset += this->header.deserialize(inbuffer + offset);
       offset += this->info.deserialize(inbuffer + offset);
-      unsigned char data_lengthT = *(inbuffer + offset++);
+      uint8_t data_lengthT = *(inbuffer + offset++);
       if(data_lengthT > data_length)
-        this->data = (signed char*)realloc(this->data, data_lengthT * sizeof(signed char));
+        this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t));
       offset += 3;
       data_length = data_lengthT;
-      for( unsigned char i = 0; i < data_length; i++){
+      for( uint8_t i = 0; i < data_length; i++){
       union {
-        signed char real;
-        unsigned char base;
+        int8_t real;
+        uint8_t base;
       } u_st_data;
       u_st_data.base = 0;
-      u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
       this->st_data = u_st_data.real;
       offset += sizeof(this->st_data);
-        memcpy( &(this->data[i]), &(this->st_data), sizeof(signed char));
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(int8_t));
       }
      return offset;
     }
 
-   virtual const char * getType(){ return "nav_msgs/OccupancyGrid"; };
+    virtual const char * getType(){ return "nav_msgs/OccupancyGrid"; };
+    virtual const char * getMD5(){ return "3381f2d731d4076ec5c71b0759edbe4e"; };
 
   };