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

Dependencies:  

Dependents:   rosserial_mbed robot_S2

Files at this revision

API Documentation at this revision

Comitter:
nucho
Date:
Sat Nov 12 23:54:45 2011 +0000
Parent:
2:bb6bb835fde4
Child:
4:684f39d0c346
Commit message:
This program supported the revision of 167 of rosserial.

Changed in this revision

MbedHardware.h Show annotated file Show diff for this revision Revisions of this file
dianostic_msgs/DiagnosticArray.h Show annotated file Show diff for this revision Revisions of this file
dianostic_msgs/DiagnosticStatus.h Show annotated file Show diff for this revision Revisions of this file
dianostic_msgs/KeyValue.h Show annotated file Show diff for this revision Revisions of this file
dianostic_msgs/SelfTest.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/Point.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/Point32.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/PointStamped.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/Polygon.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/PolygonStamped.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/Pose.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/Pose2D.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/PoseArray.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/PoseStamped.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/PoseWithCovariance.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/PoseWithCovarianceStamped.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/Quaternion.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/QuaternionStamped.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/Transform.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/TransformStamped.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/Twist.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/TwistStamped.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/TwistWithCovariance.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/TwistWithCovarianceStamped.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/Vector3.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/Vector3Stamped.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/Wrench.h Show annotated file Show diff for this revision Revisions of this file
geometry_msgs/WrenchStamped.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/GetMap.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/GetPlan.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/GridCells.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/MapMetaData.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/OccupancyGrid.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/Odometry.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/Path.h Show annotated file Show diff for this revision Revisions of this file
ros.h Show annotated file Show diff for this revision Revisions of this file
ros/duration.h Show annotated file Show diff for this revision Revisions of this file
ros/msg.h Show annotated file Show diff for this revision Revisions of this file
ros/msg_receiver.h Show diff for this revision Revisions of this file
ros/node_handle.h Show annotated file Show diff for this revision Revisions of this file
ros/node_output.h Show diff for this revision Revisions of this file
ros/publisher.h Show annotated file Show diff for this revision Revisions of this file
ros/rosserial_ids.h Show diff for this revision Revisions of this file
ros/service_client.h Show annotated file Show diff for this revision Revisions of this file
ros/service_server.h Show annotated file Show diff for this revision Revisions of this file
ros/subscriber.h Show annotated file Show diff for this revision Revisions of this file
roscpp/Empty.h Show annotated file Show diff for this revision Revisions of this file
roscpp/GetLoggers.h Show annotated file Show diff for this revision Revisions of this file
roscpp/Logger.h Show annotated file Show diff for this revision Revisions of this file
roscpp/SetLoggerLevel.h Show annotated file Show diff for this revision Revisions of this file
rosgraph_msgs/Clock.h Show annotated file Show diff for this revision Revisions of this file
rosgraph_msgs/Log.h Show annotated file Show diff for this revision Revisions of this file
rosserial_mbed/Adc.h Show diff for this revision Revisions of this file
rosserial_msgs/Log.h Show annotated file Show diff for this revision Revisions of this file
rosserial_msgs/RequestParam.h Show annotated file Show diff for this revision Revisions of this file
rosserial_msgs/TopicInfo.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/CameraInfo.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/ChannelFloat32.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/CompressedImage.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/Image.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/Imu.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/JointState.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/LaserScan.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/NavSatFix.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/NavSatStatus.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/PointCloud.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/PointCloud2.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/PointField.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/Range.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/RegionOfInterest.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/SetCameraInfo.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Bool.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Byte.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/ByteMultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Char.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/ColorRGBA.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Duration.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Empty.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Float32.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Float32MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Float64.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Float64MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Header.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Int16.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Int16MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Int32.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Int32MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Int64.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Int64MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Int8.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Int8MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/MultiArrayDimension.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/MultiArrayLayout.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/String.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Time.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/UInt16.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/UInt16MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/UInt32.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/UInt32MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/UInt64.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/UInt64MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/UInt8.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/UInt8MultiArray.h Show annotated file Show diff for this revision Revisions of this file
tests/array_test.cpp Show annotated file Show diff for this revision Revisions of this file
tests/float64_test.cpp Show annotated file Show diff for this revision Revisions of this file
tests/time_test.cpp Show annotated file Show diff for this revision Revisions of this file
tf/FrameGraph.h Show annotated file Show diff for this revision Revisions of this file
tf/tf.h Show annotated file Show diff for this revision Revisions of this file
tf/tfMessage.h Show annotated file Show diff for this revision Revisions of this file
tf/transform_broadcaster.h Show annotated file Show diff for this revision Revisions of this file
topic_tools/MuxAdd.h Show annotated file Show diff for this revision Revisions of this file
topic_tools/MuxDelete.h Show annotated file Show diff for this revision Revisions of this file
topic_tools/MuxList.h Show annotated file Show diff for this revision Revisions of this file
topic_tools/MuxSelect.h Show annotated file Show diff for this revision Revisions of this file
--- a/MbedHardware.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/MbedHardware.h	Sat Nov 12 23:54:45 2011 +0000
@@ -11,17 +11,21 @@
 #include"mbed.h"
 #include"MODSERIAL.h"
 
+#ifndef ROSSERIAL_BAUDRATE
+#define ROSSERIAL_BAUDRATE    57600
+#endif
+
 
 class MbedHardware {
 public:
-    MbedHardware(MODSERIAL* io , int baud= 57600)
+    MbedHardware(MODSERIAL* io , int baud= ROSSERIAL_BAUDRATE)
             :iostream(*io){
         baud_ = baud;
         t.start();
     }
     MbedHardware()
             :iostream(USBTX, USBRX) {
-        baud_ = 57600;
+        baud_ = ROSSERIAL_BAUDRATE;
         t.start();
     }
     MbedHardware(MbedHardware& h)
--- a/dianostic_msgs/DiagnosticArray.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/dianostic_msgs/DiagnosticArray.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,55 +1,58 @@
-#ifndef ros_diagnostic_msgs_DiagnosticArray_h
-#define ros_diagnostic_msgs_DiagnosticArray_h
+#ifndef _ROS_diagnostic_msgs_DiagnosticArray_h
+#define _ROS_diagnostic_msgs_DiagnosticArray_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "std_msgs/Header.h"
 #include "diagnostic_msgs/DiagnosticStatus.h"
 
-namespace diagnostic_msgs {
+namespace diagnostic_msgs
+{
 
-class DiagnosticArray : public ros::Msg {
-public:
-    std_msgs::Header header;
-    unsigned char status_length;
-    diagnostic_msgs::DiagnosticStatus st_status;
-    diagnostic_msgs::DiagnosticStatus * status;
+  class DiagnosticArray : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      uint8_t status_length;
+      diagnostic_msgs::DiagnosticStatus st_status;
+      diagnostic_msgs::DiagnosticStatus * status;
 
-    virtual int serialize(unsigned char *outbuffer) {
-        int offset = 0;
-        offset += this->header.serialize(outbuffer + offset);
-        *(outbuffer + offset++) = status_length;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        for ( unsigned char i = 0; i < status_length; i++) {
-            offset += this->status[i].serialize(outbuffer + offset);
-        }
-        return offset;
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = status_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < status_length; i++){
+      offset += this->status[i].serialize(outbuffer + offset);
+      }
+      return offset;
     }
 
-    virtual int deserialize(unsigned char *inbuffer) {
-        int offset = 0;
-        offset += this->header.deserialize(inbuffer + offset);
-        unsigned char status_lengthT = *(inbuffer + offset++);
-        if (status_lengthT > status_length)
-            this->status = (diagnostic_msgs::DiagnosticStatus*)realloc(this->status, status_lengthT * sizeof(diagnostic_msgs::DiagnosticStatus));
-        offset += 3;
-        status_length = status_lengthT;
-        for ( unsigned char i = 0; i < status_length; i++) {
-            offset += this->st_status.deserialize(inbuffer + offset);
-            memcpy( &(this->status[i]), &(this->st_status), sizeof(diagnostic_msgs::DiagnosticStatus));
-        }
-        return offset;
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint8_t status_lengthT = *(inbuffer + offset++);
+      if(status_lengthT > status_length)
+        this->status = (diagnostic_msgs::DiagnosticStatus*)realloc(this->status, status_lengthT * sizeof(diagnostic_msgs::DiagnosticStatus));
+      offset += 3;
+      status_length = status_lengthT;
+      for( uint8_t i = 0; i < status_length; i++){
+      offset += this->st_status.deserialize(inbuffer + offset);
+        memcpy( &(this->status[i]), &(this->st_status), sizeof(diagnostic_msgs::DiagnosticStatus));
+      }
+     return offset;
     }
 
-    virtual const char * getType() {
-        return "diagnostic_msgs/DiagnosticArray";
-    };
+    virtual const char * getType(){ return "diagnostic_msgs/DiagnosticArray"; };
+    virtual const char * getMD5(){ return "3cfbeff055e708a24c3d946a5c8139cd"; };
 
-};
+  };
 
 }
 #endif
\ No newline at end of file
--- a/dianostic_msgs/DiagnosticStatus.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/dianostic_msgs/DiagnosticStatus.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,112 +1,103 @@
-#ifndef ros_diagnostic_msgs_DiagnosticStatus_h
-#define ros_diagnostic_msgs_DiagnosticStatus_h
+#ifndef _ROS_diagnostic_msgs_DiagnosticStatus_h
+#define _ROS_diagnostic_msgs_DiagnosticStatus_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
+#include "diagnostic_msgs/byte.h"
 #include "diagnostic_msgs/KeyValue.h"
 
-namespace diagnostic_msgs {
+namespace diagnostic_msgs
+{
 
-class DiagnosticStatus : public ros::Msg {
-public:
-    unsigned char level;
-    char * name;
-    char * message;
-    char * hardware_id;
-    unsigned char values_length;
-    diagnostic_msgs::KeyValue st_values;
-    diagnostic_msgs::KeyValue * values;
-    enum { OK = 0 };
-    enum { WARN = 1 };
-    enum { ERROR = 2 };
+  class DiagnosticStatus : public ros::Msg
+  {
+    public:
+      diagnostic_msgs::byte level;
+      char * name;
+      char * message;
+      char * hardware_id;
+      uint8_t values_length;
+      diagnostic_msgs::KeyValue st_values;
+      diagnostic_msgs::KeyValue * values;
+      enum { OK = 0 };
+      enum { WARN = 1 };
+      enum { ERROR = 2 };
 
-    virtual int serialize(unsigned char *outbuffer) {
-        int offset = 0;
-        union {
-            unsigned char real;
-            unsigned char base;
-        } u_level;
-        u_level.real = this->level;
-        *(outbuffer + offset + 0) = (u_level.base >> (8 * 0)) & 0xFF;
-        offset += sizeof(this->level);
-        long * length_name = (long *)(outbuffer + offset);
-        *length_name = strlen( (const char*) this->name);
-        offset += 4;
-        memcpy(outbuffer + offset, this->name, *length_name);
-        offset += *length_name;
-        long * length_message = (long *)(outbuffer + offset);
-        *length_message = strlen( (const char*) this->message);
-        offset += 4;
-        memcpy(outbuffer + offset, this->message, *length_message);
-        offset += *length_message;
-        long * length_hardware_id = (long *)(outbuffer + offset);
-        *length_hardware_id = strlen( (const char*) this->hardware_id);
-        offset += 4;
-        memcpy(outbuffer + offset, this->hardware_id, *length_hardware_id);
-        offset += *length_hardware_id;
-        *(outbuffer + offset++) = values_length;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        for ( unsigned char i = 0; i < values_length; i++) {
-            offset += this->values[i].serialize(outbuffer + offset);
-        }
-        return offset;
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->level.serialize(outbuffer + offset);
+      uint32_t * length_name = (uint32_t *)(outbuffer + offset);
+      *length_name = strlen( (const char*) this->name);
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, *length_name);
+      offset += *length_name;
+      uint32_t * length_message = (uint32_t *)(outbuffer + offset);
+      *length_message = strlen( (const char*) this->message);
+      offset += 4;
+      memcpy(outbuffer + offset, this->message, *length_message);
+      offset += *length_message;
+      uint32_t * length_hardware_id = (uint32_t *)(outbuffer + offset);
+      *length_hardware_id = strlen( (const char*) this->hardware_id);
+      offset += 4;
+      memcpy(outbuffer + offset, this->hardware_id, *length_hardware_id);
+      offset += *length_hardware_id;
+      *(outbuffer + offset++) = values_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < values_length; i++){
+      offset += this->values[i].serialize(outbuffer + offset);
+      }
+      return offset;
     }
 
-    virtual int deserialize(unsigned char *inbuffer) {
-        int offset = 0;
-        union {
-            unsigned char real;
-            unsigned char base;
-        } u_level;
-        u_level.base = 0;
-        u_level.base |= ((typeof(u_level.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-        this->level = u_level.real;
-        offset += sizeof(this->level);
-        uint32_t length_name = *(uint32_t *)(inbuffer + offset);
-        offset += 4;
-        for (unsigned int k= offset; k< offset+length_name; ++k) {
-            inbuffer[k-1]=inbuffer[k];
-        }
-        inbuffer[offset+length_name-1]=0;
-        this->name = (char *)(inbuffer + offset-1);
-        offset += length_name;
-        uint32_t length_message = *(uint32_t *)(inbuffer + offset);
-        offset += 4;
-        for (unsigned int k= offset; k< offset+length_message; ++k) {
-            inbuffer[k-1]=inbuffer[k];
-        }
-        inbuffer[offset+length_message-1]=0;
-        this->message = (char *)(inbuffer + offset-1);
-        offset += length_message;
-        uint32_t length_hardware_id = *(uint32_t *)(inbuffer + offset);
-        offset += 4;
-        for (unsigned int k= offset; k< offset+length_hardware_id; ++k) {
-            inbuffer[k-1]=inbuffer[k];
-        }
-        inbuffer[offset+length_hardware_id-1]=0;
-        this->hardware_id = (char *)(inbuffer + offset-1);
-        offset += length_hardware_id;
-        unsigned char values_lengthT = *(inbuffer + offset++);
-        if (values_lengthT > values_length)
-            this->values = (diagnostic_msgs::KeyValue*)realloc(this->values, values_lengthT * sizeof(diagnostic_msgs::KeyValue));
-        offset += 3;
-        values_length = values_lengthT;
-        for ( unsigned char i = 0; i < values_length; i++) {
-            offset += this->st_values.deserialize(inbuffer + offset);
-            memcpy( &(this->values[i]), &(this->st_values), sizeof(diagnostic_msgs::KeyValue));
-        }
-        return offset;
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->level.deserialize(inbuffer + offset);
+      uint32_t length_name = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+      uint32_t length_message = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_message; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_message-1]=0;
+      this->message = (char *)(inbuffer + offset-1);
+      offset += length_message;
+      uint32_t length_hardware_id = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_hardware_id; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_hardware_id-1]=0;
+      this->hardware_id = (char *)(inbuffer + offset-1);
+      offset += length_hardware_id;
+      uint8_t values_lengthT = *(inbuffer + offset++);
+      if(values_lengthT > values_length)
+        this->values = (diagnostic_msgs::KeyValue*)realloc(this->values, values_lengthT * sizeof(diagnostic_msgs::KeyValue));
+      offset += 3;
+      values_length = values_lengthT;
+      for( uint8_t i = 0; i < values_length; i++){
+      offset += this->st_values.deserialize(inbuffer + offset);
+        memcpy( &(this->values[i]), &(this->st_values), sizeof(diagnostic_msgs::KeyValue));
+      }
+     return offset;
     }
 
-    virtual const char * getType() {
-        return "diagnostic_msgs/DiagnosticStatus";
-    };
+    virtual const char * getType(){ return "diagnostic_msgs/DiagnosticStatus"; };
+    virtual const char * getMD5(){ return "67d15a62edb26e9d52b0f0efa3ef9da7"; };
 
-};
+  };
 
 }
 #endif
\ No newline at end of file
--- a/dianostic_msgs/KeyValue.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/dianostic_msgs/KeyValue.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,59 +1,62 @@
-#ifndef ros_diagnostic_msgs_KeyValue_h
-#define ros_diagnostic_msgs_KeyValue_h
+#ifndef _ROS_diagnostic_msgs_KeyValue_h
+#define _ROS_diagnostic_msgs_KeyValue_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 
-namespace diagnostic_msgs {
+namespace diagnostic_msgs
+{
 
-class KeyValue : public ros::Msg {
-public:
-    char * key;
-    char * value;
+  class KeyValue : public ros::Msg
+  {
+    public:
+      char * key;
+      char * value;
 
-    virtual int serialize(unsigned char *outbuffer) {
-        int offset = 0;
-        long * length_key = (long *)(outbuffer + offset);
-        *length_key = strlen( (const char*) this->key);
-        offset += 4;
-        memcpy(outbuffer + offset, this->key, *length_key);
-        offset += *length_key;
-        long * length_value = (long *)(outbuffer + offset);
-        *length_value = strlen( (const char*) this->value);
-        offset += 4;
-        memcpy(outbuffer + offset, this->value, *length_value);
-        offset += *length_value;
-        return offset;
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t * length_key = (uint32_t *)(outbuffer + offset);
+      *length_key = strlen( (const char*) this->key);
+      offset += 4;
+      memcpy(outbuffer + offset, this->key, *length_key);
+      offset += *length_key;
+      uint32_t * length_value = (uint32_t *)(outbuffer + offset);
+      *length_value = strlen( (const char*) this->value);
+      offset += 4;
+      memcpy(outbuffer + offset, this->value, *length_value);
+      offset += *length_value;
+      return offset;
     }
 
-    virtual int deserialize(unsigned char *inbuffer) {
-        int offset = 0;
-        uint32_t length_key = *(uint32_t *)(inbuffer + offset);
-        offset += 4;
-        for (unsigned int k= offset; k< offset+length_key; ++k) {
-            inbuffer[k-1]=inbuffer[k];
-        }
-        inbuffer[offset+length_key-1]=0;
-        this->key = (char *)(inbuffer + offset-1);
-        offset += length_key;
-        uint32_t length_value = *(uint32_t *)(inbuffer + offset);
-        offset += 4;
-        for (unsigned int k= offset; k< offset+length_value; ++k) {
-            inbuffer[k-1]=inbuffer[k];
-        }
-        inbuffer[offset+length_value-1]=0;
-        this->value = (char *)(inbuffer + offset-1);
-        offset += length_value;
-        return offset;
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_key = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_key; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_key-1]=0;
+      this->key = (char *)(inbuffer + offset-1);
+      offset += length_key;
+      uint32_t length_value = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_value; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_value-1]=0;
+      this->value = (char *)(inbuffer + offset-1);
+      offset += length_value;
+     return offset;
     }
 
-    virtual const char * getType() {
-        return "diagnostic_msgs/KeyValue";
-    };
+    virtual const char * getType(){ return "diagnostic_msgs/KeyValue"; };
+    virtual const char * getMD5(){ return "cf57fdc6617a881a88c16e768132149c"; };
 
-};
+  };
 
 }
 #endif
\ No newline at end of file
--- a/dianostic_msgs/SelfTest.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/dianostic_msgs/SelfTest.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,11 @@
-#ifndef ros_SERVICE_SelfTest_h
-#define ros_SERVICE_SelfTest_h
+#ifndef _ROS_SERVICE_SelfTest_h
+#define _ROS_SERVICE_SelfTest_h
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "diagnostic_msgs/DiagnosticStatus.h"
+#include "diagnostic_msgs/byte.h"
 
 namespace diagnostic_msgs
 {
@@ -15,7 +16,7 @@
   {
     public:
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       return offset;
@@ -27,7 +28,8 @@
      return offset;
     }
 
-    const char * getType(){ return SELFTEST; };
+    virtual const char * getType(){ return SELFTEST; };
+    virtual const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
 
   };
 
@@ -35,31 +37,25 @@
   {
     public:
       char * id;
-      unsigned char passed;
-      unsigned char status_length;
+      diagnostic_msgs::byte passed;
+      uint8_t status_length;
       diagnostic_msgs::DiagnosticStatus st_status;
       diagnostic_msgs::DiagnosticStatus * status;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
-      long * length_id = (long *)(outbuffer + offset);
+      uint32_t * length_id = (uint32_t *)(outbuffer + offset);
       *length_id = strlen( (const char*) this->id);
       offset += 4;
       memcpy(outbuffer + offset, this->id, *length_id);
       offset += *length_id;
-      union {
-        unsigned char real;
-        unsigned char base;
-      } u_passed;
-      u_passed.real = this->passed;
-      *(outbuffer + offset + 0) = (u_passed.base >> (8 * 0)) & 0xFF;
-      offset += sizeof(this->passed);
+      offset += this->passed.serialize(outbuffer + offset);
       *(outbuffer + offset++) = status_length;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < status_length; i++){
+      for( uint8_t i = 0; i < status_length; i++){
       offset += this->status[i].serialize(outbuffer + offset);
       }
       return offset;
@@ -72,24 +68,17 @@
       offset += 4;
       for(unsigned int k= offset; k< offset+length_id; ++k){
           inbuffer[k-1]=inbuffer[k];
-           }
+      }
       inbuffer[offset+length_id-1]=0;
       this->id = (char *)(inbuffer + offset-1);
       offset += length_id;
-      union {
-        unsigned char real;
-        unsigned char base;
-      } u_passed;
-      u_passed.base = 0;
-      u_passed.base |= ((typeof(u_passed.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      this->passed = u_passed.real;
-      offset += sizeof(this->passed);
-      unsigned char status_lengthT = *(inbuffer + offset++);
+      offset += this->passed.deserialize(inbuffer + offset);
+      uint8_t status_lengthT = *(inbuffer + offset++);
       if(status_lengthT > status_length)
         this->status = (diagnostic_msgs::DiagnosticStatus*)realloc(this->status, status_lengthT * sizeof(diagnostic_msgs::DiagnosticStatus));
       offset += 3;
       status_length = status_lengthT;
-      for( unsigned char i = 0; i < status_length; i++){
+      for( uint8_t i = 0; i < status_length; i++){
       offset += this->st_status.deserialize(inbuffer + offset);
         memcpy( &(this->status[i]), &(this->st_status), sizeof(diagnostic_msgs::DiagnosticStatus));
       }
@@ -97,8 +86,15 @@
     }
 
     virtual const char * getType(){ return SELFTEST; };
+    virtual const char * getMD5(){ return "74c9372c870a76da4fc2b3973978b898"; };
 
   };
 
+  class SelfTest {
+    public:
+    typedef SelfTestRequest Request;
+    typedef SelfTestResponse Response;
+  };
+
 }
 #endif
\ No newline at end of file
--- a/geometry_msgs/Point.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/geometry_msgs/Point.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,109 +1,112 @@
-#ifndef ros_geometry_msgs_Point_h
-#define ros_geometry_msgs_Point_h
+#ifndef _ROS_geometry_msgs_Point_h
+#define _ROS_geometry_msgs_Point_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 
-namespace geometry_msgs {
+namespace geometry_msgs
+{
 
-class Point : public ros::Msg {
-public:
-    float x;
-    float y;
-    float z;
+  class Point : public ros::Msg
+  {
+    public:
+      float x;
+      float y;
+      float z;
 
-    virtual int serialize(unsigned char *outbuffer) {
-        int offset = 0;
-        long * val_x = (long *) &(this->x);
-        long exp_x = (((*val_x)>>23)&255);
-        if (exp_x != 0)
-            exp_x += 1023-127;
-        long sig_x = *val_x;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = (sig_x<<5) & 0xff;
-        *(outbuffer + offset++) = (sig_x>>3) & 0xff;
-        *(outbuffer + offset++) = (sig_x>>11) & 0xff;
-        *(outbuffer + offset++) = ((exp_x<<4) & 0xF0) | ((sig_x>>19)&0x0F);
-        *(outbuffer + offset++) = (exp_x>>4) & 0x7F;
-        if (this->x < 0) *(outbuffer + offset -1) |= 0x80;
-        long * val_y = (long *) &(this->y);
-        long exp_y = (((*val_y)>>23)&255);
-        if (exp_y != 0)
-            exp_y += 1023-127;
-        long sig_y = *val_y;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = (sig_y<<5) & 0xff;
-        *(outbuffer + offset++) = (sig_y>>3) & 0xff;
-        *(outbuffer + offset++) = (sig_y>>11) & 0xff;
-        *(outbuffer + offset++) = ((exp_y<<4) & 0xF0) | ((sig_y>>19)&0x0F);
-        *(outbuffer + offset++) = (exp_y>>4) & 0x7F;
-        if (this->y < 0) *(outbuffer + offset -1) |= 0x80;
-        long * val_z = (long *) &(this->z);
-        long exp_z = (((*val_z)>>23)&255);
-        if (exp_z != 0)
-            exp_z += 1023-127;
-        long sig_z = *val_z;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = (sig_z<<5) & 0xff;
-        *(outbuffer + offset++) = (sig_z>>3) & 0xff;
-        *(outbuffer + offset++) = (sig_z>>11) & 0xff;
-        *(outbuffer + offset++) = ((exp_z<<4) & 0xF0) | ((sig_z>>19)&0x0F);
-        *(outbuffer + offset++) = (exp_z>>4) & 0x7F;
-        if (this->z < 0) *(outbuffer + offset -1) |= 0x80;
-        return offset;
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      int32_t * val_x = (long *) &(this->x);
+      int32_t exp_x = (((*val_x)>>23)&255);
+      if(exp_x != 0)
+        exp_x += 1023-127;
+      int32_t sig_x = *val_x;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = (sig_x<<5) & 0xff;
+      *(outbuffer + offset++) = (sig_x>>3) & 0xff;
+      *(outbuffer + offset++) = (sig_x>>11) & 0xff;
+      *(outbuffer + offset++) = ((exp_x<<4) & 0xF0) | ((sig_x>>19)&0x0F);
+      *(outbuffer + offset++) = (exp_x>>4) & 0x7F;
+      if(this->x < 0) *(outbuffer + offset -1) |= 0x80;
+      int32_t * val_y = (long *) &(this->y);
+      int32_t exp_y = (((*val_y)>>23)&255);
+      if(exp_y != 0)
+        exp_y += 1023-127;
+      int32_t sig_y = *val_y;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = (sig_y<<5) & 0xff;
+      *(outbuffer + offset++) = (sig_y>>3) & 0xff;
+      *(outbuffer + offset++) = (sig_y>>11) & 0xff;
+      *(outbuffer + offset++) = ((exp_y<<4) & 0xF0) | ((sig_y>>19)&0x0F);
+      *(outbuffer + offset++) = (exp_y>>4) & 0x7F;
+      if(this->y < 0) *(outbuffer + offset -1) |= 0x80;
+      int32_t * val_z = (long *) &(this->z);
+      int32_t exp_z = (((*val_z)>>23)&255);
+      if(exp_z != 0)
+        exp_z += 1023-127;
+      int32_t sig_z = *val_z;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = (sig_z<<5) & 0xff;
+      *(outbuffer + offset++) = (sig_z>>3) & 0xff;
+      *(outbuffer + offset++) = (sig_z>>11) & 0xff;
+      *(outbuffer + offset++) = ((exp_z<<4) & 0xF0) | ((sig_z>>19)&0x0F);
+      *(outbuffer + offset++) = (exp_z>>4) & 0x7F;
+      if(this->z < 0) *(outbuffer + offset -1) |= 0x80;
+      return offset;
     }
 
-    virtual int deserialize(unsigned char *inbuffer) {
-        int offset = 0;
-        unsigned long * val_x = (unsigned long*) &(this->x);
-        offset += 3;
-        *val_x = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-        *val_x |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-        *val_x |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-        *val_x |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-        unsigned long exp_x = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-        exp_x |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
-        if (exp_x !=0)
-            *val_x |= ((exp_x)-1023+127)<<23;
-        if ( ((*(inbuffer+offset++)) & 0x80) > 0) this->x = -this->x;
-        unsigned long * val_y = (unsigned long*) &(this->y);
-        offset += 3;
-        *val_y = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-        *val_y |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-        *val_y |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-        *val_y |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-        unsigned long exp_y = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-        exp_y |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
-        if (exp_y !=0)
-            *val_y |= ((exp_y)-1023+127)<<23;
-        if ( ((*(inbuffer+offset++)) & 0x80) > 0) this->y = -this->y;
-        unsigned long * val_z = (unsigned long*) &(this->z);
-        offset += 3;
-        *val_z = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-        *val_z |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-        *val_z |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-        *val_z |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-        unsigned long exp_z = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-        exp_z |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
-        if (exp_z !=0)
-            *val_z |= ((exp_z)-1023+127)<<23;
-        if ( ((*(inbuffer+offset++)) & 0x80) > 0) this->z = -this->z;
-        return offset;
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t * val_x = (uint32_t*) &(this->x);
+      offset += 3;
+      *val_x = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_x |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_x = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_x |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
+      if(exp_x !=0)
+        *val_x |= ((exp_x)-1023+127)<<23;
+      if( ((*(inbuffer+offset++)) & 0x80) > 0) this->x = -this->x;
+      uint32_t * val_y = (uint32_t*) &(this->y);
+      offset += 3;
+      *val_y = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_y |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_y = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_y |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
+      if(exp_y !=0)
+        *val_y |= ((exp_y)-1023+127)<<23;
+      if( ((*(inbuffer+offset++)) & 0x80) > 0) this->y = -this->y;
+      uint32_t * val_z = (uint32_t*) &(this->z);
+      offset += 3;
+      *val_z = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_z |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_z |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_z |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_z = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_z |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
+      if(exp_z !=0)
+        *val_z |= ((exp_z)-1023+127)<<23;
+      if( ((*(inbuffer+offset++)) & 0x80) > 0) this->z = -this->z;
+     return offset;
     }
 
-    virtual const char * getType() {
-        return "geometry_msgs/Point";
-    };
+    virtual const char * getType(){ return "geometry_msgs/Point"; };
+    virtual const char * getMD5(){ return "4a842b65f413084dc2b10fb484ea7f17"; };
 
-};
+  };
 
 }
 #endif
\ No newline at end of file
--- a/geometry_msgs/Point32.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/geometry_msgs/Point32.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_geometry_msgs_Point32_h
-#define ros_geometry_msgs_Point32_h
+#ifndef _ROS_geometry_msgs_Point32_h
+#define _ROS_geometry_msgs_Point32_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 
 namespace geometry_msgs
 {
@@ -16,12 +16,12 @@
       float y;
       float z;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_x;
       u_x.real = this->x;
       *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF;
@@ -31,7 +31,7 @@
       offset += sizeof(this->x);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_y;
       u_y.real = this->y;
       *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF;
@@ -41,7 +41,7 @@
       offset += sizeof(this->y);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_z;
       u_z.real = this->z;
       *(outbuffer + offset + 0) = (u_z.base >> (8 * 0)) & 0xFF;
@@ -57,41 +57,42 @@
       int offset = 0;
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_x;
       u_x.base = 0;
-      u_x.base |= ((typeof(u_x.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_x.base |= ((typeof(u_x.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_x.base |= ((typeof(u_x.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_x.base |= ((typeof(u_x.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_x.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_x.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_x.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_x.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       this->x = u_x.real;
       offset += sizeof(this->x);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_y;
       u_y.base = 0;
-      u_y.base |= ((typeof(u_y.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_y.base |= ((typeof(u_y.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_y.base |= ((typeof(u_y.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_y.base |= ((typeof(u_y.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_y.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_y.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_y.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_y.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       this->y = u_y.real;
       offset += sizeof(this->y);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_z;
       u_z.base = 0;
-      u_z.base |= ((typeof(u_z.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_z.base |= ((typeof(u_z.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_z.base |= ((typeof(u_z.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_z.base |= ((typeof(u_z.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_z.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_z.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_z.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_z.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       this->z = u_z.real;
       offset += sizeof(this->z);
      return offset;
     }
 
     virtual const char * getType(){ return "geometry_msgs/Point32"; };
+    virtual const char * getMD5(){ return "cc153912f1453b708d221682bc23d9ac"; };
 
   };
 
--- a/geometry_msgs/PointStamped.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/geometry_msgs/PointStamped.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_geometry_msgs_PointStamped_h
-#define ros_geometry_msgs_PointStamped_h
+#ifndef _ROS_geometry_msgs_PointStamped_h
+#define _ROS_geometry_msgs_PointStamped_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "std_msgs/Header.h"
 #include "geometry_msgs/Point.h"
 
@@ -17,7 +17,7 @@
       std_msgs::Header header;
       geometry_msgs::Point point;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->header.serialize(outbuffer + offset);
@@ -34,6 +34,7 @@
     }
 
     virtual const char * getType(){ return "geometry_msgs/PointStamped"; };
+    virtual const char * getMD5(){ return "c63aecb41bfdfd6b7e1fac37c7cbe7bf"; };
 
   };
 
--- a/geometry_msgs/Polygon.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/geometry_msgs/Polygon.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,51 +1,54 @@
-#ifndef ros_geometry_msgs_Polygon_h
-#define ros_geometry_msgs_Polygon_h
+#ifndef _ROS_geometry_msgs_Polygon_h
+#define _ROS_geometry_msgs_Polygon_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "geometry_msgs/Point32.h"
 
-namespace geometry_msgs {
+namespace geometry_msgs
+{
 
-class Polygon : public ros::Msg {
-public:
-    unsigned char points_length;
-    geometry_msgs::Point32 st_points;
-    geometry_msgs::Point32 * points;
+  class Polygon : public ros::Msg
+  {
+    public:
+      uint8_t points_length;
+      geometry_msgs::Point32 st_points;
+      geometry_msgs::Point32 * points;
 
-    virtual int serialize(unsigned char *outbuffer) {
-        int offset = 0;
-        *(outbuffer + offset++) = points_length;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        for ( unsigned char i = 0; i < points_length; i++) {
-            offset += this->points[i].serialize(outbuffer + offset);
-        }
-        return offset;
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = points_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < points_length; i++){
+      offset += this->points[i].serialize(outbuffer + offset);
+      }
+      return offset;
     }
 
-    virtual int deserialize(unsigned char *inbuffer) {
-        int offset = 0;
-        unsigned char points_lengthT = *(inbuffer + offset++);
-        if (points_lengthT > points_length)
-            this->points = (geometry_msgs::Point32*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point32));
-        offset += 3;
-        points_length = points_lengthT;
-        for ( unsigned char i = 0; i < points_length; i++) {
-            offset += this->st_points.deserialize(inbuffer + offset);
-            memcpy( &(this->points[i]), &(this->st_points), sizeof(geometry_msgs::Point32));
-        }
-        return offset;
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t points_lengthT = *(inbuffer + offset++);
+      if(points_lengthT > points_length)
+        this->points = (geometry_msgs::Point32*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point32));
+      offset += 3;
+      points_length = points_lengthT;
+      for( uint8_t i = 0; i < points_length; i++){
+      offset += this->st_points.deserialize(inbuffer + offset);
+        memcpy( &(this->points[i]), &(this->st_points), sizeof(geometry_msgs::Point32));
+      }
+     return offset;
     }
 
-    virtual const char * getType() {
-        return "geometry_msgs/Polygon";
-    };
+    virtual const char * getType(){ return "geometry_msgs/Polygon"; };
+    virtual const char * getMD5(){ return "cd60a26494a087f577976f0329fa120e"; };
 
-};
+  };
 
 }
 #endif
\ No newline at end of file
--- a/geometry_msgs/PolygonStamped.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/geometry_msgs/PolygonStamped.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_geometry_msgs_PolygonStamped_h
-#define ros_geometry_msgs_PolygonStamped_h
+#ifndef _ROS_geometry_msgs_PolygonStamped_h
+#define _ROS_geometry_msgs_PolygonStamped_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "std_msgs/Header.h"
 #include "geometry_msgs/Polygon.h"
 
@@ -17,7 +17,7 @@
       std_msgs::Header header;
       geometry_msgs::Polygon polygon;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->header.serialize(outbuffer + offset);
@@ -33,7 +33,8 @@
      return offset;
     }
 
-   virtual const char * getType(){ return "geometry_msgs/PolygonStamped"; };
+    virtual const char * getType(){ return "geometry_msgs/PolygonStamped"; };
+    virtual const char * getMD5(){ return "c6be8f7dc3bee7fe9e8d296070f53340"; };
 
   };
 
--- a/geometry_msgs/Pose.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/geometry_msgs/Pose.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_geometry_msgs_Pose_h
-#define ros_geometry_msgs_Pose_h
+#ifndef _ROS_geometry_msgs_Pose_h
+#define _ROS_geometry_msgs_Pose_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "geometry_msgs/Point.h"
 #include "geometry_msgs/Quaternion.h"
 
@@ -17,7 +17,7 @@
       geometry_msgs::Point position;
       geometry_msgs::Quaternion orientation;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->position.serialize(outbuffer + offset);
@@ -33,7 +33,8 @@
      return offset;
     }
 
-   virtual virtual const char * getType(){ return "geometry_msgs/Pose"; };
+    virtual const char * getType(){ return "geometry_msgs/Pose"; };
+    virtual const char * getMD5(){ return "e45d45a5a1ce597b249e23fb30fc871f"; };
 
   };
 
--- a/geometry_msgs/Pose2D.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/geometry_msgs/Pose2D.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_geometry_msgs_Pose2D_h
-#define ros_geometry_msgs_Pose2D_h
+#ifndef _ROS_geometry_msgs_Pose2D_h
+#define _ROS_geometry_msgs_Pose2D_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 
 namespace geometry_msgs
 {
@@ -16,14 +16,14 @@
       float y;
       float theta;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
-      long * val_x = (long *) &(this->x);
-      long exp_x = (((*val_x)>>23)&255);
+      int32_t * val_x = (long *) &(this->x);
+      int32_t exp_x = (((*val_x)>>23)&255);
       if(exp_x != 0)
         exp_x += 1023-127;
-      long sig_x = *val_x;
+      int32_t sig_x = *val_x;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
@@ -33,11 +33,11 @@
       *(outbuffer + offset++) = ((exp_x<<4) & 0xF0) | ((sig_x>>19)&0x0F);
       *(outbuffer + offset++) = (exp_x>>4) & 0x7F;
       if(this->x < 0) *(outbuffer + offset -1) |= 0x80;
-      long * val_y = (long *) &(this->y);
-      long exp_y = (((*val_y)>>23)&255);
+      int32_t * val_y = (long *) &(this->y);
+      int32_t exp_y = (((*val_y)>>23)&255);
       if(exp_y != 0)
         exp_y += 1023-127;
-      long sig_y = *val_y;
+      int32_t sig_y = *val_y;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
@@ -47,11 +47,11 @@
       *(outbuffer + offset++) = ((exp_y<<4) & 0xF0) | ((sig_y>>19)&0x0F);
       *(outbuffer + offset++) = (exp_y>>4) & 0x7F;
       if(this->y < 0) *(outbuffer + offset -1) |= 0x80;
-      long * val_theta = (long *) &(this->theta);
-      long exp_theta = (((*val_theta)>>23)&255);
+      int32_t * val_theta = (long *) &(this->theta);
+      int32_t exp_theta = (((*val_theta)>>23)&255);
       if(exp_theta != 0)
         exp_theta += 1023-127;
-      long sig_theta = *val_theta;
+      int32_t sig_theta = *val_theta;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
@@ -67,43 +67,44 @@
     virtual int deserialize(unsigned char *inbuffer)
     {
       int offset = 0;
-      unsigned long * val_x = (unsigned long*) &(this->x);
+      uint32_t * val_x = (uint32_t*) &(this->x);
       offset += 3;
-      *val_x = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-      *val_x |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-      *val_x |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-      *val_x |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-      unsigned long exp_x = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-      exp_x |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      *val_x = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_x |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_x = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_x |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
       if(exp_x !=0)
         *val_x |= ((exp_x)-1023+127)<<23;
       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->x = -this->x;
-      unsigned long * val_y = (unsigned long*) &(this->y);
+      uint32_t * val_y = (uint32_t*) &(this->y);
       offset += 3;
-      *val_y = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-      *val_y |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-      *val_y |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-      *val_y |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-      unsigned long exp_y = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-      exp_y |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      *val_y = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_y |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_y = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_y |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
       if(exp_y !=0)
         *val_y |= ((exp_y)-1023+127)<<23;
       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->y = -this->y;
-      unsigned long * val_theta = (unsigned long*) &(this->theta);
+      uint32_t * val_theta = (uint32_t*) &(this->theta);
       offset += 3;
-      *val_theta = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-      *val_theta |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-      *val_theta |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-      *val_theta |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-      unsigned long exp_theta = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-      exp_theta |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      *val_theta = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_theta |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_theta |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_theta |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_theta = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_theta |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
       if(exp_theta !=0)
         *val_theta |= ((exp_theta)-1023+127)<<23;
       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->theta = -this->theta;
      return offset;
     }
 
-   virtual const char * getType(){ return "geometry_msgs/Pose2D"; };
+    virtual const char * getType(){ return "geometry_msgs/Pose2D"; };
+    virtual const char * getMD5(){ return "938fa65709584ad8e77d238529be13b8"; };
 
   };
 
--- a/geometry_msgs/PoseArray.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/geometry_msgs/PoseArray.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_geometry_msgs_PoseArray_h
-#define ros_geometry_msgs_PoseArray_h
+#ifndef _ROS_geometry_msgs_PoseArray_h
+#define _ROS_geometry_msgs_PoseArray_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "std_msgs/Header.h"
 #include "geometry_msgs/Pose.h"
 
@@ -15,11 +15,11 @@
   {
     public:
       std_msgs::Header header;
-      unsigned char poses_length;
+      uint8_t poses_length;
       geometry_msgs::Pose st_poses;
       geometry_msgs::Pose * poses;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->header.serialize(outbuffer + offset);
@@ -27,7 +27,7 @@
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < poses_length; i++){
+      for( uint8_t i = 0; i < poses_length; i++){
       offset += this->poses[i].serialize(outbuffer + offset);
       }
       return offset;
@@ -37,12 +37,12 @@
     {
       int offset = 0;
       offset += this->header.deserialize(inbuffer + offset);
-      unsigned char poses_lengthT = *(inbuffer + offset++);
+      uint8_t poses_lengthT = *(inbuffer + offset++);
       if(poses_lengthT > poses_length)
         this->poses = (geometry_msgs::Pose*)realloc(this->poses, poses_lengthT * sizeof(geometry_msgs::Pose));
       offset += 3;
       poses_length = poses_lengthT;
-      for( unsigned char i = 0; i < poses_length; i++){
+      for( uint8_t i = 0; i < poses_length; i++){
       offset += this->st_poses.deserialize(inbuffer + offset);
         memcpy( &(this->poses[i]), &(this->st_poses), sizeof(geometry_msgs::Pose));
       }
@@ -50,6 +50,7 @@
     }
 
     virtual const char * getType(){ return "geometry_msgs/PoseArray"; };
+    virtual const char * getMD5(){ return "916c28c5764443f268b296bb671b9d97"; };
 
   };
 
--- a/geometry_msgs/PoseStamped.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/geometry_msgs/PoseStamped.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_geometry_msgs_PoseStamped_h
-#define ros_geometry_msgs_PoseStamped_h
+#ifndef _ROS_geometry_msgs_PoseStamped_h
+#define _ROS_geometry_msgs_PoseStamped_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "std_msgs/Header.h"
 #include "geometry_msgs/Pose.h"
 
@@ -17,7 +17,7 @@
       std_msgs::Header header;
       geometry_msgs::Pose pose;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->header.serialize(outbuffer + offset);
@@ -33,7 +33,8 @@
      return offset;
     }
 
-   virtual const char * getType(){ return "geometry_msgs/PoseStamped"; };
+    virtual const char * getType(){ return "geometry_msgs/PoseStamped"; };
+    virtual const char * getMD5(){ return "d3812c3cbc69362b77dc0b19b345f8f5"; };
 
   };
 
--- a/geometry_msgs/PoseWithCovariance.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/geometry_msgs/PoseWithCovariance.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_geometry_msgs_PoseWithCovariance_h
-#define ros_geometry_msgs_PoseWithCovariance_h
+#ifndef _ROS_geometry_msgs_PoseWithCovariance_h
+#define _ROS_geometry_msgs_PoseWithCovariance_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "geometry_msgs/Pose.h"
 
 namespace geometry_msgs
@@ -16,17 +16,17 @@
       geometry_msgs::Pose pose;
       float covariance[36];
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->pose.serialize(outbuffer + offset);
       unsigned char * covariance_val = (unsigned char *) this->covariance;
-      for( unsigned char i = 0; i < 36; i++){
-      long * val_covariancei = (long *) &(this->covariance[i]);
-      long exp_covariancei = (((*val_covariancei)>>23)&255);
+      for( uint8_t i = 0; i < 36; i++){
+      int32_t * val_covariancei = (long *) &(this->covariance[i]);
+      int32_t exp_covariancei = (((*val_covariancei)>>23)&255);
       if(exp_covariancei != 0)
         exp_covariancei += 1023-127;
-      long sig_covariancei = *val_covariancei;
+      int32_t sig_covariancei = *val_covariancei;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
@@ -44,16 +44,16 @@
     {
       int offset = 0;
       offset += this->pose.deserialize(inbuffer + offset);
-      unsigned char * covariance_val = (unsigned char *) this->covariance;
-      for( unsigned char i = 0; i < 36; i++){
-      unsigned long * val_covariancei = (unsigned long*) &(this->covariance[i]);
+      uint8_t * covariance_val = (uint8_t*) this->covariance;
+      for( uint8_t i = 0; i < 36; i++){
+      uint32_t * val_covariancei = (uint32_t*) &(this->covariance[i]);
       offset += 3;
-      *val_covariancei = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-      *val_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-      *val_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-      *val_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-      unsigned long exp_covariancei = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-      exp_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      *val_covariancei = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_covariancei = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
       if(exp_covariancei !=0)
         *val_covariancei |= ((exp_covariancei)-1023+127)<<23;
       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->covariance[i] = -this->covariance[i];
@@ -61,7 +61,8 @@
      return offset;
     }
 
-   virtual const char * getType(){ return "geometry_msgs/PoseWithCovariance"; };
+    virtual const char * getType(){ return "geometry_msgs/PoseWithCovariance"; };
+    virtual const char * getMD5(){ return "c23e848cf1b7533a8d7c259073a97e6f"; };
 
   };
 
--- a/geometry_msgs/PoseWithCovarianceStamped.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/geometry_msgs/PoseWithCovarianceStamped.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_geometry_msgs_PoseWithCovarianceStamped_h
-#define ros_geometry_msgs_PoseWithCovarianceStamped_h
+#ifndef _ROS_geometry_msgs_PoseWithCovarianceStamped_h
+#define _ROS_geometry_msgs_PoseWithCovarianceStamped_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "std_msgs/Header.h"
 #include "geometry_msgs/PoseWithCovariance.h"
 
@@ -17,7 +17,7 @@
       std_msgs::Header header;
       geometry_msgs::PoseWithCovariance pose;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->header.serialize(outbuffer + offset);
@@ -33,7 +33,8 @@
      return offset;
     }
 
-   virtual const char * getType(){ return "geometry_msgs/PoseWithCovarianceStamped"; };
+    virtual const char * getType(){ return "geometry_msgs/PoseWithCovarianceStamped"; };
+    virtual const char * getMD5(){ return "953b798c0f514ff060a53a3498ce6246"; };
 
   };
 
--- a/geometry_msgs/Quaternion.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/geometry_msgs/Quaternion.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_geometry_msgs_Quaternion_h
-#define ros_geometry_msgs_Quaternion_h
+#ifndef _ROS_geometry_msgs_Quaternion_h
+#define _ROS_geometry_msgs_Quaternion_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 
 namespace geometry_msgs
 {
@@ -17,14 +17,14 @@
       float z;
       float w;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
-      long * val_x = (long *) &(this->x);
-      long exp_x = (((*val_x)>>23)&255);
+      int32_t * val_x = (long *) &(this->x);
+      int32_t exp_x = (((*val_x)>>23)&255);
       if(exp_x != 0)
         exp_x += 1023-127;
-      long sig_x = *val_x;
+      int32_t sig_x = *val_x;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
@@ -34,11 +34,11 @@
       *(outbuffer + offset++) = ((exp_x<<4) & 0xF0) | ((sig_x>>19)&0x0F);
       *(outbuffer + offset++) = (exp_x>>4) & 0x7F;
       if(this->x < 0) *(outbuffer + offset -1) |= 0x80;
-      long * val_y = (long *) &(this->y);
-      long exp_y = (((*val_y)>>23)&255);
+      int32_t * val_y = (long *) &(this->y);
+      int32_t exp_y = (((*val_y)>>23)&255);
       if(exp_y != 0)
         exp_y += 1023-127;
-      long sig_y = *val_y;
+      int32_t sig_y = *val_y;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
@@ -48,11 +48,11 @@
       *(outbuffer + offset++) = ((exp_y<<4) & 0xF0) | ((sig_y>>19)&0x0F);
       *(outbuffer + offset++) = (exp_y>>4) & 0x7F;
       if(this->y < 0) *(outbuffer + offset -1) |= 0x80;
-      long * val_z = (long *) &(this->z);
-      long exp_z = (((*val_z)>>23)&255);
+      int32_t * val_z = (long *) &(this->z);
+      int32_t exp_z = (((*val_z)>>23)&255);
       if(exp_z != 0)
         exp_z += 1023-127;
-      long sig_z = *val_z;
+      int32_t sig_z = *val_z;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
@@ -62,11 +62,11 @@
       *(outbuffer + offset++) = ((exp_z<<4) & 0xF0) | ((sig_z>>19)&0x0F);
       *(outbuffer + offset++) = (exp_z>>4) & 0x7F;
       if(this->z < 0) *(outbuffer + offset -1) |= 0x80;
-      long * val_w = (long *) &(this->w);
-      long exp_w = (((*val_w)>>23)&255);
+      int32_t * val_w = (long *) &(this->w);
+      int32_t exp_w = (((*val_w)>>23)&255);
       if(exp_w != 0)
         exp_w += 1023-127;
-      long sig_w = *val_w;
+      int32_t sig_w = *val_w;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
@@ -82,47 +82,47 @@
     virtual int deserialize(unsigned char *inbuffer)
     {
       int offset = 0;
-      unsigned long * val_x = (unsigned long*) &(this->x);
+      uint32_t * val_x = (uint32_t*) &(this->x);
       offset += 3;
-      *val_x = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-      *val_x |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-      *val_x |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-      *val_x |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-      unsigned long exp_x = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-      exp_x |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      *val_x = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_x |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_x = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_x |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
       if(exp_x !=0)
         *val_x |= ((exp_x)-1023+127)<<23;
       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->x = -this->x;
-      unsigned long * val_y = (unsigned long*) &(this->y);
+      uint32_t * val_y = (uint32_t*) &(this->y);
       offset += 3;
-      *val_y = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-      *val_y |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-      *val_y |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-      *val_y |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-      unsigned long exp_y = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-      exp_y |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      *val_y = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_y |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_y = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_y |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
       if(exp_y !=0)
         *val_y |= ((exp_y)-1023+127)<<23;
       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->y = -this->y;
-      unsigned long * val_z = (unsigned long*) &(this->z);
+      uint32_t * val_z = (uint32_t*) &(this->z);
       offset += 3;
-      *val_z = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-      *val_z |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-      *val_z |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-      *val_z |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-      unsigned long exp_z = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-      exp_z |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      *val_z = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_z |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_z |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_z |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_z = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_z |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
       if(exp_z !=0)
         *val_z |= ((exp_z)-1023+127)<<23;
       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->z = -this->z;
-      unsigned long * val_w = (unsigned long*) &(this->w);
+      uint32_t * val_w = (uint32_t*) &(this->w);
       offset += 3;
-      *val_w = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-      *val_w |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-      *val_w |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-      *val_w |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-      unsigned long exp_w = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-      exp_w |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      *val_w = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_w |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_w |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_w |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_w = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_w |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
       if(exp_w !=0)
         *val_w |= ((exp_w)-1023+127)<<23;
       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->w = -this->w;
@@ -130,6 +130,7 @@
     }
 
     virtual const char * getType(){ return "geometry_msgs/Quaternion"; };
+    virtual const char * getMD5(){ return "a779879fadf0160734f906b8c19c7004"; };
 
   };
 
--- a/geometry_msgs/QuaternionStamped.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/geometry_msgs/QuaternionStamped.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,11 +1,10 @@
-#ifndef ros_geometry_msgs_QuaternionStamped_h
-#define ros_geometry_msgs_QuaternionStamped_h
-
+#ifndef _ROS_geometry_msgs_QuaternionStamped_h
+#define _ROS_geometry_msgs_QuaternionStamped_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "std_msgs/Header.h"
 #include "geometry_msgs/Quaternion.h"
 
@@ -18,7 +17,7 @@
       std_msgs::Header header;
       geometry_msgs::Quaternion quaternion;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->header.serialize(outbuffer + offset);
@@ -34,7 +33,8 @@
      return offset;
     }
 
-   virtual const char * getType(){ return "geometry_msgs/QuaternionStamped"; };
+    virtual const char * getType(){ return "geometry_msgs/QuaternionStamped"; };
+    virtual const char * getMD5(){ return "e57f1e547e0e1fd13504588ffc8334e2"; };
 
   };
 
--- a/geometry_msgs/Transform.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/geometry_msgs/Transform.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_geometry_msgs_Transform_h
-#define ros_geometry_msgs_Transform_h
+#ifndef _ROS_geometry_msgs_Transform_h
+#define _ROS_geometry_msgs_Transform_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "geometry_msgs/Vector3.h"
 #include "geometry_msgs/Quaternion.h"
 
@@ -17,7 +17,7 @@
       geometry_msgs::Vector3 translation;
       geometry_msgs::Quaternion rotation;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->translation.serialize(outbuffer + offset);
@@ -34,6 +34,7 @@
     }
 
     virtual const char * getType(){ return "geometry_msgs/Transform"; };
+    virtual const char * getMD5(){ return "ac9eff44abf714214112b05d54a3cf9b"; };
 
   };
 
--- a/geometry_msgs/TransformStamped.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/geometry_msgs/TransformStamped.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_geometry_msgs_TransformStamped_h
-#define ros_geometry_msgs_TransformStamped_h
+#ifndef _ROS_geometry_msgs_TransformStamped_h
+#define _ROS_geometry_msgs_TransformStamped_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "std_msgs/Header.h"
 #include "geometry_msgs/Transform.h"
 
@@ -18,11 +18,11 @@
       char * child_frame_id;
       geometry_msgs::Transform transform;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->header.serialize(outbuffer + offset);
-      long * length_child_frame_id = (long *)(outbuffer + offset);
+      uint32_t * length_child_frame_id = (uint32_t *)(outbuffer + offset);
       *length_child_frame_id = strlen( (const char*) this->child_frame_id);
       offset += 4;
       memcpy(outbuffer + offset, this->child_frame_id, *length_child_frame_id);
@@ -39,7 +39,7 @@
       offset += 4;
       for(unsigned int k= offset; k< offset+length_child_frame_id; ++k){
           inbuffer[k-1]=inbuffer[k];
-           }
+      }
       inbuffer[offset+length_child_frame_id-1]=0;
       this->child_frame_id = (char *)(inbuffer + offset-1);
       offset += length_child_frame_id;
@@ -48,6 +48,7 @@
     }
 
     virtual const char * getType(){ return "geometry_msgs/TransformStamped"; };
+    virtual const char * getMD5(){ return "b5764a33bfeb3588febc2682852579b0"; };
 
   };
 
--- a/geometry_msgs/Twist.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/geometry_msgs/Twist.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_geometry_msgs_Twist_h
-#define ros_geometry_msgs_Twist_h
+#ifndef _ROS_geometry_msgs_Twist_h
+#define _ROS_geometry_msgs_Twist_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "geometry_msgs/Vector3.h"
 
 namespace geometry_msgs
@@ -16,7 +16,7 @@
       geometry_msgs::Vector3 linear;
       geometry_msgs::Vector3 angular;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->linear.serialize(outbuffer + offset);
@@ -32,7 +32,8 @@
      return offset;
     }
 
-   virtual const char * getType(){ return "geometry_msgs/Twist"; };
+    virtual const char * getType(){ return "geometry_msgs/Twist"; };
+    virtual const char * getMD5(){ return "9f195f881246fdfa2798d1d3eebca84a"; };
 
   };
 
--- a/geometry_msgs/TwistStamped.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/geometry_msgs/TwistStamped.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_geometry_msgs_TwistStamped_h
-#define ros_geometry_msgs_TwistStamped_h
+#ifndef _ROS_geometry_msgs_TwistStamped_h
+#define _ROS_geometry_msgs_TwistStamped_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "std_msgs/Header.h"
 #include "geometry_msgs/Twist.h"
 
@@ -17,7 +17,7 @@
       std_msgs::Header header;
       geometry_msgs::Twist twist;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->header.serialize(outbuffer + offset);
@@ -33,7 +33,8 @@
      return offset;
     }
 
-   virtual const char * getType(){ return "geometry_msgs/TwistStamped"; };
+    virtual const char * getType(){ return "geometry_msgs/TwistStamped"; };
+    virtual const char * getMD5(){ return "98d34b0043a2093cf9d9345ab6eef12e"; };
 
   };
 
--- a/geometry_msgs/TwistWithCovariance.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/geometry_msgs/TwistWithCovariance.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_geometry_msgs_TwistWithCovariance_h
-#define ros_geometry_msgs_TwistWithCovariance_h
+#ifndef _ROS_geometry_msgs_TwistWithCovariance_h
+#define _ROS_geometry_msgs_TwistWithCovariance_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "geometry_msgs/Twist.h"
 
 namespace geometry_msgs
@@ -16,17 +16,17 @@
       geometry_msgs::Twist twist;
       float covariance[36];
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->twist.serialize(outbuffer + offset);
       unsigned char * covariance_val = (unsigned char *) this->covariance;
-      for( unsigned char i = 0; i < 36; i++){
-      long * val_covariancei = (long *) &(this->covariance[i]);
-      long exp_covariancei = (((*val_covariancei)>>23)&255);
+      for( uint8_t i = 0; i < 36; i++){
+      int32_t * val_covariancei = (long *) &(this->covariance[i]);
+      int32_t exp_covariancei = (((*val_covariancei)>>23)&255);
       if(exp_covariancei != 0)
         exp_covariancei += 1023-127;
-      long sig_covariancei = *val_covariancei;
+      int32_t sig_covariancei = *val_covariancei;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
@@ -44,16 +44,16 @@
     {
       int offset = 0;
       offset += this->twist.deserialize(inbuffer + offset);
-      unsigned char * covariance_val = (unsigned char *) this->covariance;
-      for( unsigned char i = 0; i < 36; i++){
-      unsigned long * val_covariancei = (unsigned long*) &(this->covariance[i]);
+      uint8_t * covariance_val = (uint8_t*) this->covariance;
+      for( uint8_t i = 0; i < 36; i++){
+      uint32_t * val_covariancei = (uint32_t*) &(this->covariance[i]);
       offset += 3;
-      *val_covariancei = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-      *val_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-      *val_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-      *val_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-      unsigned long exp_covariancei = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-      exp_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      *val_covariancei = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_covariancei = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
       if(exp_covariancei !=0)
         *val_covariancei |= ((exp_covariancei)-1023+127)<<23;
       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->covariance[i] = -this->covariance[i];
@@ -61,7 +61,8 @@
      return offset;
     }
 
-   virtual const char * getType(){ return "geometry_msgs/TwistWithCovariance"; };
+    virtual const char * getType(){ return "geometry_msgs/TwistWithCovariance"; };
+    virtual const char * getMD5(){ return "1fe8a28e6890a4cc3ae4c3ca5c7d82e6"; };
 
   };
 
--- a/geometry_msgs/TwistWithCovarianceStamped.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/geometry_msgs/TwistWithCovarianceStamped.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_geometry_msgs_TwistWithCovarianceStamped_h
-#define ros_geometry_msgs_TwistWithCovarianceStamped_h
+#ifndef _ROS_geometry_msgs_TwistWithCovarianceStamped_h
+#define _ROS_geometry_msgs_TwistWithCovarianceStamped_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "std_msgs/Header.h"
 #include "geometry_msgs/TwistWithCovariance.h"
 
@@ -17,7 +17,7 @@
       std_msgs::Header header;
       geometry_msgs::TwistWithCovariance twist;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->header.serialize(outbuffer + offset);
@@ -33,7 +33,8 @@
      return offset;
     }
 
-   virtual const char * getType(){ return "geometry_msgs/TwistWithCovarianceStamped"; };
+    virtual const char * getType(){ return "geometry_msgs/TwistWithCovarianceStamped"; };
+    virtual const char * getMD5(){ return "8927a1a12fb2607ceea095b2dc440a96"; };
 
   };
 
--- a/geometry_msgs/Vector3.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/geometry_msgs/Vector3.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_geometry_msgs_Vector3_h
-#define ros_geometry_msgs_Vector3_h
+#ifndef _ROS_geometry_msgs_Vector3_h
+#define _ROS_geometry_msgs_Vector3_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 
 namespace geometry_msgs
 {
@@ -16,14 +16,14 @@
       float y;
       float z;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
-      long * val_x = (long *) &(this->x);
-      long exp_x = (((*val_x)>>23)&255);
+      int32_t * val_x = (long *) &(this->x);
+      int32_t exp_x = (((*val_x)>>23)&255);
       if(exp_x != 0)
         exp_x += 1023-127;
-      long sig_x = *val_x;
+      int32_t sig_x = *val_x;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
@@ -33,11 +33,11 @@
       *(outbuffer + offset++) = ((exp_x<<4) & 0xF0) | ((sig_x>>19)&0x0F);
       *(outbuffer + offset++) = (exp_x>>4) & 0x7F;
       if(this->x < 0) *(outbuffer + offset -1) |= 0x80;
-      long * val_y = (long *) &(this->y);
-      long exp_y = (((*val_y)>>23)&255);
+      int32_t * val_y = (long *) &(this->y);
+      int32_t exp_y = (((*val_y)>>23)&255);
       if(exp_y != 0)
         exp_y += 1023-127;
-      long sig_y = *val_y;
+      int32_t sig_y = *val_y;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
@@ -47,11 +47,11 @@
       *(outbuffer + offset++) = ((exp_y<<4) & 0xF0) | ((sig_y>>19)&0x0F);
       *(outbuffer + offset++) = (exp_y>>4) & 0x7F;
       if(this->y < 0) *(outbuffer + offset -1) |= 0x80;
-      long * val_z = (long *) &(this->z);
-      long exp_z = (((*val_z)>>23)&255);
+      int32_t * val_z = (long *) &(this->z);
+      int32_t exp_z = (((*val_z)>>23)&255);
       if(exp_z != 0)
         exp_z += 1023-127;
-      long sig_z = *val_z;
+      int32_t sig_z = *val_z;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
@@ -67,36 +67,36 @@
     virtual int deserialize(unsigned char *inbuffer)
     {
       int offset = 0;
-      unsigned long * val_x = (unsigned long*) &(this->x);
+      uint32_t * val_x = (uint32_t*) &(this->x);
       offset += 3;
-      *val_x = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-      *val_x |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-      *val_x |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-      *val_x |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-      unsigned long exp_x = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-      exp_x |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      *val_x = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_x |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_x |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_x = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_x |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
       if(exp_x !=0)
         *val_x |= ((exp_x)-1023+127)<<23;
       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->x = -this->x;
-      unsigned long * val_y = (unsigned long*) &(this->y);
+      uint32_t * val_y = (uint32_t*) &(this->y);
       offset += 3;
-      *val_y = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-      *val_y |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-      *val_y |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-      *val_y |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-      unsigned long exp_y = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-      exp_y |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      *val_y = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_y |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_y |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_y = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_y |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
       if(exp_y !=0)
         *val_y |= ((exp_y)-1023+127)<<23;
       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->y = -this->y;
-      unsigned long * val_z = (unsigned long*) &(this->z);
+      uint32_t * val_z = (uint32_t*) &(this->z);
       offset += 3;
-      *val_z = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-      *val_z |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-      *val_z |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-      *val_z |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-      unsigned long exp_z = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-      exp_z |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      *val_z = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_z |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_z |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_z |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_z = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_z |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
       if(exp_z !=0)
         *val_z |= ((exp_z)-1023+127)<<23;
       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->z = -this->z;
@@ -104,6 +104,7 @@
     }
 
     virtual const char * getType(){ return "geometry_msgs/Vector3"; };
+    virtual const char * getMD5(){ return "4a842b65f413084dc2b10fb484ea7f17"; };
 
   };
 
--- a/geometry_msgs/Vector3Stamped.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/geometry_msgs/Vector3Stamped.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_geometry_msgs_Vector3Stamped_h
-#define ros_geometry_msgs_Vector3Stamped_h
+#ifndef _ROS_geometry_msgs_Vector3Stamped_h
+#define _ROS_geometry_msgs_Vector3Stamped_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "std_msgs/Header.h"
 #include "geometry_msgs/Vector3.h"
 
@@ -17,7 +17,7 @@
       std_msgs::Header header;
       geometry_msgs::Vector3 vector;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->header.serialize(outbuffer + offset);
@@ -33,7 +33,8 @@
      return offset;
     }
 
-   virtual const char * getType(){ return "geometry_msgs/Vector3Stamped"; };
+    virtual const char * getType(){ return "geometry_msgs/Vector3Stamped"; };
+    virtual const char * getMD5(){ return "7b324c7325e683bf02a9b14b01090ec7"; };
 
   };
 
--- a/geometry_msgs/Wrench.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/geometry_msgs/Wrench.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,11 +1,10 @@
-#ifndef ros_geometry_msgs_Wrench_h
-#define ros_geometry_msgs_Wrench_h
-
+#ifndef _ROS_geometry_msgs_Wrench_h
+#define _ROS_geometry_msgs_Wrench_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "geometry_msgs/Vector3.h"
 
 namespace geometry_msgs
@@ -17,7 +16,7 @@
       geometry_msgs::Vector3 force;
       geometry_msgs::Vector3 torque;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->force.serialize(outbuffer + offset);
@@ -33,7 +32,8 @@
      return offset;
     }
 
-   virtual const char * getType(){ return "geometry_msgs/Wrench"; };
+    virtual const char * getType(){ return "geometry_msgs/Wrench"; };
+    virtual const char * getMD5(){ return "4f539cf138b23283b520fd271b567936"; };
 
   };
 
--- a/geometry_msgs/WrenchStamped.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/geometry_msgs/WrenchStamped.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_geometry_msgs_WrenchStamped_h
-#define ros_geometry_msgs_WrenchStamped_h
+#ifndef _ROS_geometry_msgs_WrenchStamped_h
+#define _ROS_geometry_msgs_WrenchStamped_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "std_msgs/Header.h"
 #include "geometry_msgs/Wrench.h"
 
@@ -17,7 +17,7 @@
       std_msgs::Header header;
       geometry_msgs::Wrench wrench;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->header.serialize(outbuffer + offset);
@@ -33,7 +33,8 @@
      return offset;
     }
 
-   virtual const char * getType(){ return "geometry_msgs/WrenchStamped"; };
+    virtual const char * getType(){ return "geometry_msgs/WrenchStamped"; };
+    virtual const char * getMD5(){ return "d78d3cb249ce23087ade7e7d0c40cfa7"; };
 
   };
 
--- a/nav_msgs/GetMap.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/nav_msgs/GetMap.h	Sat Nov 12 23:54:45 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;
   };
 
 }
--- a/nav_msgs/GetPlan.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/nav_msgs/GetPlan.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,9 +1,9 @@
-#ifndef ros_SERVICE_GetPlan_h
-#define ros_SERVICE_GetPlan_h
+#ifndef _ROS_SERVICE_GetPlan_h
+#define _ROS_SERVICE_GetPlan_h
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "geometry_msgs/PoseStamped.h"
 #include "nav_msgs/Path.h"
 
@@ -19,14 +19,14 @@
       geometry_msgs::PoseStamped goal;
       float tolerance;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->start.serialize(outbuffer + offset);
       offset += this->goal.serialize(outbuffer + offset);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_tolerance;
       u_tolerance.real = this->tolerance;
       *(outbuffer + offset + 0) = (u_tolerance.base >> (8 * 0)) & 0xFF;
@@ -44,19 +44,20 @@
       offset += this->goal.deserialize(inbuffer + offset);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_tolerance;
       u_tolerance.base = 0;
-      u_tolerance.base |= ((typeof(u_tolerance.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_tolerance.base |= ((typeof(u_tolerance.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_tolerance.base |= ((typeof(u_tolerance.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_tolerance.base |= ((typeof(u_tolerance.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       this->tolerance = u_tolerance.real;
       offset += sizeof(this->tolerance);
      return offset;
     }
 
-    const char * getType(){ return GETPLAN; };
+    virtual const char * getType(){ return GETPLAN; };
+    virtual const char * getMD5(){ return "e25a43e0752bcca599a8c2eef8282df8"; };
 
   };
 
@@ -65,7 +66,7 @@
     public:
       nav_msgs::Path plan;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->plan.serialize(outbuffer + offset);
@@ -79,8 +80,15 @@
      return offset;
     }
 
-   virtual const char * getType(){ return GETPLAN; };
+    virtual const char * getType(){ return GETPLAN; };
+    virtual const char * getMD5(){ return "0002bc113c0259d71f6cf8cbc9430e18"; };
+
+  };
 
+  class GetPlan {
+    public:
+    typedef GetPlanRequest Request;
+    typedef GetPlanResponse Response;
   };
 
 }
--- a/nav_msgs/GridCells.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/nav_msgs/GridCells.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_nav_msgs_GridCells_h
-#define ros_nav_msgs_GridCells_h
+#ifndef _ROS_nav_msgs_GridCells_h
+#define _ROS_nav_msgs_GridCells_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "std_msgs/Header.h"
 #include "geometry_msgs/Point.h"
 
@@ -17,17 +17,17 @@
       std_msgs::Header header;
       float cell_width;
       float cell_height;
-      unsigned char cells_length;
+      uint8_t cells_length;
       geometry_msgs::Point st_cells;
       geometry_msgs::Point * cells;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->header.serialize(outbuffer + offset);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_cell_width;
       u_cell_width.real = this->cell_width;
       *(outbuffer + offset + 0) = (u_cell_width.base >> (8 * 0)) & 0xFF;
@@ -37,7 +37,7 @@
       offset += sizeof(this->cell_width);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_cell_height;
       u_cell_height.real = this->cell_height;
       *(outbuffer + offset + 0) = (u_cell_height.base >> (8 * 0)) & 0xFF;
@@ -49,7 +49,7 @@
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < cells_length; i++){
+      for( uint8_t i = 0; i < cells_length; i++){
       offset += this->cells[i].serialize(outbuffer + offset);
       }
       return offset;
@@ -61,39 +61,40 @@
       offset += this->header.deserialize(inbuffer + offset);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_cell_width;
       u_cell_width.base = 0;
-      u_cell_width.base |= ((typeof(u_cell_width.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_cell_width.base |= ((typeof(u_cell_width.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_cell_width.base |= ((typeof(u_cell_width.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_cell_width.base |= ((typeof(u_cell_width.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_cell_width.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_cell_width.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_cell_width.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_cell_width.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       this->cell_width = u_cell_width.real;
       offset += sizeof(this->cell_width);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_cell_height;
       u_cell_height.base = 0;
-      u_cell_height.base |= ((typeof(u_cell_height.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_cell_height.base |= ((typeof(u_cell_height.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_cell_height.base |= ((typeof(u_cell_height.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_cell_height.base |= ((typeof(u_cell_height.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_cell_height.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_cell_height.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_cell_height.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_cell_height.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       this->cell_height = u_cell_height.real;
       offset += sizeof(this->cell_height);
-      unsigned char cells_lengthT = *(inbuffer + offset++);
+      uint8_t cells_lengthT = *(inbuffer + offset++);
       if(cells_lengthT > cells_length)
         this->cells = (geometry_msgs::Point*)realloc(this->cells, cells_lengthT * sizeof(geometry_msgs::Point));
       offset += 3;
       cells_length = cells_lengthT;
-      for( unsigned char i = 0; i < cells_length; i++){
+      for( uint8_t i = 0; i < cells_length; i++){
       offset += this->st_cells.deserialize(inbuffer + offset);
         memcpy( &(this->cells[i]), &(this->st_cells), sizeof(geometry_msgs::Point));
       }
      return offset;
     }
 
-   virtual const char * getType(){ return "nav_msgs/GridCells"; };
+    virtual const char * getType(){ return "nav_msgs/GridCells"; };
+    virtual const char * getMD5(){ return "b9e4f5df6d28e272ebde00a3994830f5"; };
 
   };
 
--- a/nav_msgs/MapMetaData.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/nav_msgs/MapMetaData.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_nav_msgs_MapMetaData_h
-#define ros_nav_msgs_MapMetaData_h
+#ifndef _ROS_nav_msgs_MapMetaData_h
+#define _ROS_nav_msgs_MapMetaData_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "ros/time.h"
 #include "geometry_msgs/Pose.h"
 
@@ -16,36 +16,26 @@
     public:
       ros::Time map_load_time;
       float resolution;
-      unsigned long width;
-      unsigned long height;
+      uint32_t width;
+      uint32_t height;
       geometry_msgs::Pose origin;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_sec;
-      u_sec.real = this->map_load_time.sec;
-      *(outbuffer + offset + 0) = (u_sec.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_sec.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_sec.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_sec.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->map_load_time.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->map_load_time.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->map_load_time.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->map_load_time.sec >> (8 * 3)) & 0xFF;
       offset += sizeof(this->map_load_time.sec);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_nsec;
-      u_nsec.real = this->map_load_time.nsec;
-      *(outbuffer + offset + 0) = (u_nsec.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_nsec.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_nsec.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_nsec.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->map_load_time.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->map_load_time.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->map_load_time.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->map_load_time.nsec >> (8 * 3)) & 0xFF;
       offset += sizeof(this->map_load_time.nsec);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_resolution;
       u_resolution.real = this->resolution;
       *(outbuffer + offset + 0) = (u_resolution.base >> (8 * 0)) & 0xFF;
@@ -53,25 +43,15 @@
       *(outbuffer + offset + 2) = (u_resolution.base >> (8 * 2)) & 0xFF;
       *(outbuffer + offset + 3) = (u_resolution.base >> (8 * 3)) & 0xFF;
       offset += sizeof(this->resolution);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_width;
-      u_width.real = this->width;
-      *(outbuffer + offset + 0) = (u_width.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_width.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_width.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_width.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF;
       offset += sizeof(this->width);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_height;
-      u_height.real = this->height;
-      *(outbuffer + offset + 0) = (u_height.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_height.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_height.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_height.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF;
       offset += sizeof(this->height);
       offset += this->origin.serialize(outbuffer + offset);
       return offset;
@@ -80,66 +60,43 @@
     virtual int deserialize(unsigned char *inbuffer)
     {
       int offset = 0;
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_sec;
-      u_sec.base = 0;
-      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->map_load_time.sec = u_sec.real;
+      this->map_load_time.sec |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->map_load_time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->map_load_time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->map_load_time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       offset += sizeof(this->map_load_time.sec);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_nsec;
-      u_nsec.base = 0;
-      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->map_load_time.nsec = u_nsec.real;
+      this->map_load_time.nsec |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->map_load_time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->map_load_time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->map_load_time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       offset += sizeof(this->map_load_time.nsec);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_resolution;
       u_resolution.base = 0;
-      u_resolution.base |= ((typeof(u_resolution.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_resolution.base |= ((typeof(u_resolution.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_resolution.base |= ((typeof(u_resolution.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_resolution.base |= ((typeof(u_resolution.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_resolution.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_resolution.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_resolution.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_resolution.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       this->resolution = u_resolution.real;
       offset += sizeof(this->resolution);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_width;
-      u_width.base = 0;
-      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->width = u_width.real;
+      this->width |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       offset += sizeof(this->width);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_height;
-      u_height.base = 0;
-      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->height = u_height.real;
+      this->height |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       offset += sizeof(this->height);
       offset += this->origin.deserialize(inbuffer + offset);
      return offset;
     }
 
-   virtual const char * getType(){ return "nav_msgs/MapMetaData"; };
+    virtual const char * getType(){ return "nav_msgs/MapMetaData"; };
+    virtual const char * getMD5(){ return "10cfc8a2818024d3248802c00c95f11b"; };
 
   };
 
--- 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"; };
 
   };
 
--- a/nav_msgs/Odometry.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/nav_msgs/Odometry.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_nav_msgs_Odometry_h
-#define ros_nav_msgs_Odometry_h
+#ifndef _ROS_nav_msgs_Odometry_h
+#define _ROS_nav_msgs_Odometry_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "std_msgs/Header.h"
 #include "geometry_msgs/PoseWithCovariance.h"
 #include "geometry_msgs/TwistWithCovariance.h"
@@ -20,11 +20,11 @@
       geometry_msgs::PoseWithCovariance pose;
       geometry_msgs::TwistWithCovariance twist;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->header.serialize(outbuffer + offset);
-      long * length_child_frame_id = (long *)(outbuffer + offset);
+      uint32_t * length_child_frame_id = (uint32_t *)(outbuffer + offset);
       *length_child_frame_id = strlen( (const char*) this->child_frame_id);
       offset += 4;
       memcpy(outbuffer + offset, this->child_frame_id, *length_child_frame_id);
@@ -42,7 +42,7 @@
       offset += 4;
       for(unsigned int k= offset; k< offset+length_child_frame_id; ++k){
           inbuffer[k-1]=inbuffer[k];
-           }
+      }
       inbuffer[offset+length_child_frame_id-1]=0;
       this->child_frame_id = (char *)(inbuffer + offset-1);
       offset += length_child_frame_id;
@@ -51,7 +51,8 @@
      return offset;
     }
 
-   virtual const char * getType(){ return "nav_msgs/Odometry"; };
+    virtual const char * getType(){ return "nav_msgs/Odometry"; };
+    virtual const char * getMD5(){ return "cd5e73d190d741a2f92e81eda573aca7"; };
 
   };
 
--- a/nav_msgs/Path.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/nav_msgs/Path.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_nav_msgs_Path_h
-#define ros_nav_msgs_Path_h
+#ifndef _ROS_nav_msgs_Path_h
+#define _ROS_nav_msgs_Path_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "std_msgs/Header.h"
 #include "geometry_msgs/PoseStamped.h"
 
@@ -15,11 +15,11 @@
   {
     public:
       std_msgs::Header header;
-      unsigned char poses_length;
+      uint8_t poses_length;
       geometry_msgs::PoseStamped st_poses;
       geometry_msgs::PoseStamped * poses;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->header.serialize(outbuffer + offset);
@@ -27,7 +27,7 @@
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < poses_length; i++){
+      for( uint8_t i = 0; i < poses_length; i++){
       offset += this->poses[i].serialize(outbuffer + offset);
       }
       return offset;
@@ -37,19 +37,20 @@
     {
       int offset = 0;
       offset += this->header.deserialize(inbuffer + offset);
-      unsigned char poses_lengthT = *(inbuffer + offset++);
+      uint8_t poses_lengthT = *(inbuffer + offset++);
       if(poses_lengthT > poses_length)
         this->poses = (geometry_msgs::PoseStamped*)realloc(this->poses, poses_lengthT * sizeof(geometry_msgs::PoseStamped));
       offset += 3;
       poses_length = poses_lengthT;
-      for( unsigned char i = 0; i < poses_length; i++){
+      for( uint8_t i = 0; i < poses_length; i++){
       offset += this->st_poses.deserialize(inbuffer + offset);
         memcpy( &(this->poses[i]), &(this->st_poses), sizeof(geometry_msgs::PoseStamped));
       }
      return offset;
     }
 
-   virtual const char * getType(){ return "nav_msgs/Path"; };
+    virtual const char * getType(){ return "nav_msgs/Path"; };
+    virtual const char * getMD5(){ return "6227e2b7e9cce15051f669a5e197bbf7"; };
 
   };
 
--- a/ros.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/ros.h	Sat Nov 12 23:54:45 2011 +0000
@@ -32,8 +32,8 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#ifndef ros_h
-#define ros_h
+#ifndef _ROS_H
+#define _ROS_H
 
 #include "ros/node_handle.h"
 #include "MbedHardware.h"
--- a/ros/duration.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/ros/duration.h	Sat Nov 12 23:54:45 2011 +0000
@@ -32,8 +32,8 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#ifndef ROS_DURATION_H_
-#define ROS_DURATION_H_
+#ifndef _ROS_DURATION_H_
+#define _ROS_DURATION_H_
 
 namespace ros {
 
--- a/ros/msg.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/ros/msg.h	Sat Nov 12 23:54:45 2011 +0000
@@ -32,8 +32,8 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#ifndef ROS_MSG_H_
-#define ROS_MSG_H_
+#ifndef _ROS_MSG_H_
+#define _ROS_MSG_H_
 
 
 namespace ros {
@@ -42,9 +42,10 @@
   class Msg
   {
     public:
-      virtual int serialize(unsigned char *outbuffer) = 0;
+      virtual int serialize(unsigned char *outbuffer) const = 0;
       virtual int deserialize(unsigned char *data) = 0;
       virtual const char * getType() = 0;
+      virtual const char * getMD5() = 0;
   };
 
 }
--- a/ros/msg_receiver.h	Sun Oct 16 09:35:11 2011 +0000
+++ /dev/null	Thu Jan 01 00:00:00 1970 +0000
@@ -1,55 +0,0 @@
-/* 
- * Software License Agreement (BSD License)
- *
- * Copyright (c) 2011, Willow Garage, Inc.
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- *  * Redistributions of source code must retain the above copyright
- *    notice, this list of conditions and the following disclaimer.
- *  * Redistributions in binary form must reproduce the above
- *    copyright notice, this list of conditions and the following
- *    disclaimer in the documentation and/or other materials provided
- *    with the distribution.
- *  * Neither the name of Willow Garage, Inc. nor the names of its
- *    contributors may be used to endorse or promote prducts derived
- *    from this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-#ifndef ROS_MSG_RECEIVER_H_
-#define ROS_MSG_RECEIVER_H_
-
-namespace ros {
-
-  /* Base class for objects recieving messages (Services and Subscribers) */
-  class MsgReceiver
-  {
-    public:
-      virtual void receive(unsigned char *data)=0;
-
-      //Distinguishes between different receiver types
-      virtual int _getType()=0;
-      virtual const char * getMsgType()=0;
-      short id_;
-      const char * topic_;
-  };
-
-}
-
-#endif
\ No newline at end of file
--- a/ros/node_handle.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/ros/node_handle.h	Sat Nov 12 23:54:45 2011 +0000
@@ -35,10 +35,10 @@
 #ifndef ROS_NODE_HANDLE_H_
 #define ROS_NODE_HANDLE_H_
 
-#include "../std_msgs/Time.h"
-#include "../rosserial_msgs/TopicInfo.h"
-#include "../rosserial_msgs/Log.h"
-#include "../rosserial_msgs/RequestParam.h"
+#include "std_msgs/Time.h"
+#include "rosserial_msgs/TopicInfo.h"
+#include "rosserial_msgs/Log.h"
+#include "rosserial_msgs/RequestParam.h"
 
 #define SYNC_SECONDS        5
 
@@ -53,13 +53,24 @@
 
 #define MSG_TIMEOUT 20  //20 milliseconds to recieve all of message data
 
-#include "node_output.h"
+#include "msg.h"
+
+namespace ros {
+
+class NodeHandleBase_ {
+public:
+    virtual int publish(int16_t id, const Msg* msg)=0;
+    virtual int spinOnce()=0;
+    virtual bool connected()=0;
+};
+
+}
 
 #include "publisher.h"
-#include "msg_receiver.h"
 #include "subscriber.h"
-#include "rosserial_ids.h"
 #include "service_server.h"
+#include "service_client.h"
+
 
 namespace ros {
 
@@ -71,10 +82,9 @@
 int MAX_PUBLISHERS=25,
 int INPUT_SIZE=512,
 int OUTPUT_SIZE=512>
-class NodeHandle_ {
+class NodeHandle_ : public NodeHandleBase_ {
 protected:
     Hardware hardware_;
-    NodeOutput<Hardware, OUTPUT_SIZE> no_;
 
     /* time used for syncing */
     unsigned long rt_time;
@@ -83,15 +93,16 @@
     unsigned long sec_offset, nsec_offset;
 
     unsigned char message_in[INPUT_SIZE];
+    unsigned char message_out[OUTPUT_SIZE];
 
     Publisher * publishers[MAX_PUBLISHERS];
-    MsgReceiver * receivers[MAX_SUBSCRIBERS];
+    Subscriber_ * subscribers[MAX_SUBSCRIBERS];
 
     /*
      * Setup Functions
      */
 public:
-    NodeHandle_() : no_(&hardware_) {}
+    NodeHandle_() : configured_(false) {}
 
     Hardware* getHardware() {
         return &hardware_;
@@ -105,18 +116,18 @@
         index_ = 0;
         topic_ = 0;
         checksum_=0;
-
-        total_receivers=0;
     };
 
 protected:
-    //State machine variables for spinOnce
+//State machine variables for spinOnce
     int mode_;
     int bytes_;
     int topic_;
     int index_;
     int checksum_;
 
+    bool configured_;
+
     int total_receivers;
 
     /* used for syncing the time */
@@ -124,26 +135,17 @@
     unsigned long last_sync_receive_time;
     unsigned long last_msg_timeout_time;
 
-    bool registerReceiver(MsgReceiver* rcv) {
-        if (total_receivers >= MAX_SUBSCRIBERS)
-            return false;
-        receivers[total_receivers] = rcv;
-        rcv->id_ = 100+total_receivers;
-        total_receivers++;
-        return true;
-    }
-
 public:
     /* This function goes in your loop() function, it handles
      *  serial input and callbacks for subscribers.
      */
 
-    virtual void spinOnce() {
+    virtual int spinOnce() {
 
         /* restart if timed out */
         unsigned long c_time = hardware_.time();
         if ( (c_time - last_sync_receive_time) > (SYNC_SECONDS*2200) ) {
-            no_.setConfigured(false);
+            configured_ = false;
         }
 
         /* reset if message has timed out */
@@ -192,45 +194,48 @@
                 if (bytes_ == 0)
                     mode_ = MODE_CHECKSUM;
             } else if ( mode_ == MODE_CHECKSUM ) { /* do checksum */
+                mode_ = MODE_FIRST_FF;
                 if ( (checksum_%256) == 255) {
-                    if (topic_ == TOPIC_NEGOTIATION) {
+                    if (topic_ == TopicInfo::ID_PUBLISHER) {
                         requestSyncTime();
                         negotiateTopics();
                         last_sync_time = c_time;
                         last_sync_receive_time = c_time;
+                        return -1;
                     } else if (topic_ == TopicInfo::ID_TIME) {
                         syncTime(message_in);
                     } else if (topic_ == TopicInfo::ID_PARAMETER_REQUEST) {
                         req_param_resp.deserialize(message_in);
                         param_recieved= true;
                     } else {
-                        if (receivers[topic_-100])
-                            receivers[topic_-100]->receive( message_in );
+                        if (subscribers[topic_-100])
+                            subscribers[topic_-100]->callback( message_in );
                     }
                 }
-                mode_ = MODE_FIRST_FF;
             }
         }
 
         /* occasionally sync time */
-        if ( no_.configured() && ((c_time-last_sync_time) > (SYNC_SECONDS*500) )) {
+        if ( configured_ && ((c_time-last_sync_time) > (SYNC_SECONDS*500) )) {
             requestSyncTime();
             last_sync_time = c_time;
         }
+
+        return 0;
     }
 
     /* Are we connected to the PC? */
-    bool connected() {
-        return no_.configured();
+    virtual bool connected() {
+        return configured_;
     };
 
-    /*
+    /********************************************************************
      * Time functions
      */
 
     void requestSyncTime() {
         std_msgs::Time t;
-        no_.publish( rosserial_msgs::TopicInfo::ID_TIME, &t);
+        publish(TopicInfo::ID_TIME, &t);
         rt_time = hardware_.time();
     }
 
@@ -263,37 +268,66 @@
         normalizeSecNSec(sec_offset, nsec_offset);
     }
 
-    /*
-     * Registration
+    /********************************************************************
+     * Topic Management
      */
 
+    /* Register a new publisher */
     bool advertise(Publisher & p) {
-        int i;
-        for (i = 0; i < MAX_PUBLISHERS; i++) {
+        for (int i = 0; i < MAX_PUBLISHERS; i++) {
             if (publishers[i] == 0) { // empty slot
                 publishers[i] = &p;
                 p.id_ = i+100+MAX_SUBSCRIBERS;
-                p.no_ = &this->no_;
+                p.nh_ = this;
+                return true;
+            }
+        }
+        return false;
+    }
+
+    /* Register a new subscriber */
+    template<typename MsgT>
+    bool subscribe(Subscriber< MsgT> & s) {
+        for (int i = 0; i < MAX_SUBSCRIBERS; i++) {
+            if (subscribers[i] == 0) { // empty slot
+                subscribers[i] = (Subscriber_*) &s;
+                s.id_ = i+100;
                 return true;
             }
         }
         return false;
     }
 
-    /* Register a subscriber with the node */
-    template<typename MsgT>
-    bool subscribe(Subscriber< MsgT> &s) {
-        return registerReceiver((MsgReceiver*) &s);
+    /* Register a new Service Server */
+    template<typename MReq, typename MRes>
+    bool advertiseService(ServiceServer<MReq,MRes>& srv) {
+        bool v = advertise(srv.pub);
+        for (int i = 0; i < MAX_SUBSCRIBERS; i++) {
+            if (subscribers[i] == 0) { // empty slot
+                subscribers[i] = (Subscriber_*) &srv;
+                srv.id_ = i+100;
+                return v;
+            }
+        }
+        return false;
     }
 
-    template<typename SrvReq, typename SrvResp>
-    bool advertiseService(ServiceServer<SrvReq,SrvResp>& srv) {
-        srv.no_ = &no_;
-        return registerReceiver((MsgReceiver*) &srv);
+    /* Register a new Service Client */
+    template<typename MReq, typename MRes>
+    bool serviceClient(ServiceClient<MReq, MRes>& srv) {
+        bool v = advertise(srv.pub);
+        for (int i = 0; i < MAX_SUBSCRIBERS; i++) {
+            if (subscribers[i] == 0) { // empty slot
+                subscribers[i] = (Subscriber_*) &srv;
+                srv.id_ = i+100;
+                return v;
+            }
+        }
+        return false;
     }
 
     void negotiateTopics() {
-        no_.setConfigured(true);
+        configured_ = true;
         rosserial_msgs::TopicInfo ti;
         int i;
         for (i = 0; i < MAX_PUBLISHERS; i++) {
@@ -301,20 +335,57 @@
                 ti.topic_id = publishers[i]->id_;
                 ti.topic_name = (char *) publishers[i]->topic_;
                 ti.message_type = (char *) publishers[i]->msg_->getType();
-                no_.publish( TOPIC_PUBLISHERS, &ti );
+                ti.md5sum = (char *) publishers[i]->msg_->getMD5();
+                ti.buffer_size = OUTPUT_SIZE;
+
+                publish( publishers[i]->getEndpointType(), &ti );
             }
         }
         for (i = 0; i < MAX_SUBSCRIBERS; i++) {
-            if (receivers[i] != 0) { // non-empty slot
-                ti.topic_id = receivers[i]->id_;
-                ti.topic_name = (char *) receivers[i]->topic_;
-                ti.message_type = (char *) receivers[i]->getMsgType();
-                no_.publish( TOPIC_SUBSCRIBERS, &ti );
+            if (subscribers[i] != 0) { // non-empty slot
+                ti.topic_id = subscribers[i]->id_;
+                ti.topic_name = (char *) subscribers[i]->topic_;
+                ti.message_type = (char *) subscribers[i]->getMsgType();
+                ti.md5sum = (char *) subscribers[i]->getMsgMD5();
+                ti.buffer_size = INPUT_SIZE;
+                publish( subscribers[i]->getEndpointType(), &ti );
             }
         }
     }
 
-    /*
+    virtual int publish(int16_t id, const Msg * msg)
+    {
+        if (!configured_) return 0;
+
+        /* serialize message */
+        int16_t l = msg->serialize(message_out+6);
+
+        /* setup the header */
+        message_out[0] = 0xff;
+        message_out[1] = 0xff;
+        message_out[2] = (unsigned char) id&255;
+        message_out[3] = (unsigned char) id>>8;
+        message_out[4] = (unsigned char) l&255;
+        message_out[5] = ((unsigned char) l>>8);
+
+        /* calculate checksum */
+        int chk = 0;
+        for (int i =2; i<l+6; i++)
+            chk += message_out[i];
+        l += 6;
+        message_out[l++] = 255 - (chk%256);
+
+        if ( l <= OUTPUT_SIZE ) {
+            hardware_.write(message_out, l);
+            return l;
+        } else {
+            logerror("Message from device dropped: message larger than buffer.");
+            return 1;
+        }
+
+    }
+
+     /********************************************************************
      * Logging
      */
 
@@ -323,7 +394,7 @@
         rosserial_msgs::Log l;
         l.level= byte;
         l.msg = (char*)msg;
-        this->no_.publish(rosserial_msgs::TopicInfo::ID_LOG, &l);
+        publish(rosserial_msgs::TopicInfo::ID_LOG, &l);
     }
 
 public:
@@ -344,8 +415,8 @@
     }
 
 
-    /*
-     * Retrieve Parameters
+    /********************************************************************
+     * Parameters
      */
 
 private:
@@ -356,7 +427,7 @@
         param_recieved = false;
         rosserial_msgs::RequestParamRequest req;
         req.name  = (char*)name;
-        no_.publish(TopicInfo::ID_PARAMETER_REQUEST, &req);
+        publish(TopicInfo::ID_PARAMETER_REQUEST, &req);
         int end_time = hardware_.time();
         while (!param_recieved ) {
             spinOnce();
--- a/ros/node_output.h	Sun Oct 16 09:35:11 2011 +0000
+++ /dev/null	Thu Jan 01 00:00:00 1970 +0000
@@ -1,111 +0,0 @@
-/*
- * Software License Agreement (BSD License)
- *
- * Copyright (c) 2011, Willow Garage, Inc.
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- *  * Redistributions of source code must retain the above copyright
- *    notice, this list of conditions and the following disclaimer.
- *  * Redistributions in binary form must reproduce the above
- *    copyright notice, this list of conditions and the following
- *    disclaimer in the documentation and/or other materials provided
- *    with the distribution.
- *  * Neither the name of Willow Garage, Inc. nor the names of its
- *    contributors may be used to endorse or promote prducts derived
- *    from this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-#ifndef ROS_NODEOUTPUT_H_
-#define ROS_NODEOUTPUT_H_
-
-#include "msg.h"
-
-#include "mbed.h"
-//static Serial debug(p9,p10);
-
-namespace ros {
-
-/*
- * This class is responsible for controlling the node ouput.
- * It it is the object that is passed to Publishers and services
- */
-class NodeOutput_ {
-public:
-    virtual int publish(short id, Msg* msg)=0;
-};
-
-template<class Hardware, int OUTSIZE =512>
-class NodeOutput : public NodeOutput_ {
-
-private:
-    Hardware* hardware_;
-    bool configured_;
-    unsigned char message_out[OUTSIZE];
-
-public:
-    NodeOutput(Hardware* h) {
-        hardware_ = h;
-        configured_ = false;
-    }
-
-    NodeOutput() {};
-
-    void setHardware(Hardware* h) {
-        hardware_  = h;
-        configured_=false;
-    }
-
-    void setConfigured(bool b) {
-        configured_ =b;
-    }
-    bool configured() {
-        return configured_;
-    };
-
-    virtual int publish(short id, Msg * msg) {
-        wait_ms(1);
-        if (!configured_)return 0;
-
-        /* serialize message */
-        short l = msg->serialize(message_out+6);
-
-        /* setup the header */
-        message_out[0] = 0xff;
-        message_out[1] = 0xff;
-        message_out[2] = (unsigned char) id&255;
-        message_out[3] = (unsigned char) id>>8;
-        message_out[4] = (unsigned char) l&255;
-        message_out[5] = ((unsigned char) l>>8);
-
-        /* calculate checksum */
-        short chk = 0;
-        for (int i =2; i<l+6; i++)
-            chk += message_out[i];
-        l += 6;
-        message_out[l++] = 255 - (chk%256);
-
-        hardware_->write(message_out, l);
-        return l;
-    }
-};
-
-}
-
-#endif
\ No newline at end of file
--- a/ros/publisher.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/ros/publisher.h	Sat Nov 12 23:54:45 2011 +0000
@@ -32,10 +32,11 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#ifndef PUBLISHER_H_
-#define PUBLISHER_H_
+#ifndef _ROS_PUBLISHER_H_
+#define _ROS_PUBLISHER_H_
 
-#include "node_output.h"
+#include "rosserial_msgs/TopicInfo.h"
+#include "node_handle.h"
 
 namespace ros{
 
@@ -43,17 +44,23 @@
   class Publisher
   {
     public:
-      Publisher( const char * topic_name, Msg * msg ): topic_(topic_name), msg_(msg){};
-      int publish( Msg * msg ){
-          return no_->publish(id_, msg_);
-      };
+      Publisher( const char * topic_name, Msg * msg, int endpoint=rosserial_msgs::TopicInfo::ID_PUBLISHER) :
+        topic_(topic_name), 
+        msg_(msg),
+        endpoint_(endpoint) {};
+
+      int publish( const Msg * msg ) { return nh_->publish(id_, msg); };
+      int getEndpointType(){ return endpoint_; }
 
       const char * topic_;
 
       Msg *msg_;
-      short id_;
-      NodeOutput_* no_;
+      // id_ and no_ are set by NodeHandle when we advertise 
+      int16_t id_;
+      NodeHandleBase_* nh_;
 
+    private:
+      int endpoint_;
   };
 
 }
--- a/ros/rosserial_ids.h	Sun Oct 16 09:35:11 2011 +0000
+++ /dev/null	Thu Jan 01 00:00:00 1970 +0000
@@ -1,43 +0,0 @@
-/* 
- * Software License Agreement (BSD License)
- *
- * Copyright (c) 2011, Willow Garage, Inc.
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- *  * Redistributions of source code must retain the above copyright
- *    notice, this list of conditions and the following disclaimer.
- *  * Redistributions in binary form must reproduce the above
- *    copyright notice, this list of conditions and the following
- *    disclaimer in the documentation and/or other materials provided
- *    with the distribution.
- *  * Neither the name of Willow Garage, Inc. nor the names of its
- *    contributors may be used to endorse or promote prducts derived
- *    from this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-#ifndef ROS_ROSSERIAL_IDS_H_
-#define ROS_ROSSERIAL_IDS_H_
-
-#define TOPIC_NEGOTIATION   0
-#define TOPIC_PUBLISHERS    0
-#define TOPIC_SUBSCRIBERS   1
-#define TOPIC_SERVICES      2
-
-#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/service_client.h	Sat Nov 12 23:54:45 2011 +0000
@@ -0,0 +1,83 @@
+/* 
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2011, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ *  * Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  * Redistributions in binary form must reproduce the above
+ *    copyright notice, this list of conditions and the following
+ *    disclaimer in the documentation and/or other materials provided
+ *    with the distribution.
+ *  * Neither the name of Willow Garage, Inc. nor the names of its
+ *    contributors may be used to endorse or promote prducts derived
+ *    from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef _ROS_SERVICE_CLIENT_H_
+#define _ROS_SERVICE_CLIENT_H_
+
+#include "rosserial_msgs/TopicInfo.h"
+
+#include "publisher.h"
+#include "subscriber.h"
+
+namespace ros {
+
+  template<typename MReq , typename MRes>
+  class ServiceClient : public Subscriber_  {
+    public:
+      ServiceClient(const char* topic_name) : 
+        pub(topic_name, &req, rosserial_msgs::TopicInfo::ID_SERVICE_CLIENT + rosserial_msgs::TopicInfo::ID_PUBLISHER)
+      {
+        this->topic_ = topic_name;
+        this->waiting = true;
+      }
+
+      virtual void call(const MReq & request, MRes & response)
+      {
+        if(!pub.nh_->connected()) return;
+        ret = &response;
+        waiting = true;
+        pub.publish(&request);
+        while(waiting && pub.nh_->connected())
+          if(pub.nh_->spinOnce() < 0) break;
+      }
+
+      // these refer to the subscriber
+      virtual void callback(unsigned char *data){
+        ret->deserialize(data);
+        waiting = false;
+      }
+      virtual const char * getMsgType(){ return this->resp.getType(); }
+      virtual const char * getMsgMD5(){ return this->resp.getMD5(); }
+      virtual int getEndpointType(){ return rosserial_msgs::TopicInfo::ID_SERVICE_CLIENT + rosserial_msgs::TopicInfo::ID_SUBSCRIBER; }
+
+      MReq req;
+      MRes resp;
+      MRes * ret;
+      bool waiting;
+      Publisher pub;
+  };
+
+}
+
+#endif
\ No newline at end of file
--- a/ros/service_server.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/ros/service_server.h	Sat Nov 12 23:54:45 2011 +0000
@@ -32,46 +32,41 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#ifndef ROS_SERVICE_SERVER_H_
-#define ROS_SERVICE_SERVER_H_
+#ifndef _ROS_SERVICE_SERVER_H_
+#define _ROS_SERVICE_SERVER_H_
 
-#include "node_output.h"
+#include "rosserial_msgs/TopicInfo.h"
+
+#include "publisher.h"
+#include "subscriber.h"
 
 namespace ros {
 
-  template<typename SrvRequest , typename SrvResponse>
-  class ServiceServer : MsgReceiver{
+  template<typename MReq , typename MRes>
+  class ServiceServer : public Subscriber_ {
     public:
-      typedef void(*CallbackT)(const SrvRequest&,  SrvResponse&);
+      typedef void(*CallbackT)(const MReq&,  MRes&);
 
-      ServiceServer(const char* topic_name, CallbackT cb){
+      ServiceServer(const char* topic_name, CallbackT cb) :
+        pub(topic_name, &resp, rosserial_msgs::TopicInfo::ID_SERVICE_SERVER + rosserial_msgs::TopicInfo::ID_PUBLISHER)
+      {
         this->topic_ = topic_name;
         this->cb_ = cb;
       }
 
-      ServiceServer(ServiceServer& srv){
-        this->topic_ = srv.topic_;
-        this->cb_ = srv.cb_;
+      // these refer to the subscriber
+      virtual void callback(unsigned char *data){
+        req.deserialize(data);
+        cb_(req,resp);
+        pub.publish(&resp);
       }
-
-      virtual void receive(unsigned char * data){
-        req.deserialize(data);
-        this->cb_(req, resp);
-        no_->publish(id_, &resp);
-      }
+      virtual const char * getMsgType(){ return this->req.getType(); }
+      virtual const char * getMsgMD5(){ return this->req.getMD5(); }
+      virtual int getEndpointType(){ return rosserial_msgs::TopicInfo::ID_SERVICE_SERVER + rosserial_msgs::TopicInfo::ID_SUBSCRIBER; }
 
-      virtual int _getType(){
-        return 3;
-      }
-     
-      virtual const char * getMsgType(){
-        return req.getType();
-      }
-
-      SrvRequest req;
-      SrvResponse resp;
-      NodeOutput_ * no_;
-
+      MReq req;
+      MRes resp;
+      Publisher pub;
     private:
       CallbackT cb_;
   };
--- a/ros/subscriber.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/ros/subscriber.h	Sat Nov 12 23:54:45 2011 +0000
@@ -35,37 +35,52 @@
 #ifndef ROS_SUBSCRIBER_H_
 #define ROS_SUBSCRIBER_H_
 
-#include "rosserial_ids.h"
-#include "msg_receiver.h"
+#include "rosserial_msgs/TopicInfo.h"
 
 namespace ros {
 
-  /* ROS Subscriber
-   * This class handles holding the msg so that
-   * it is not continously reallocated.  It is also used by the
-   * node handle to keep track of callback functions and IDs.
-   */
+  /* Base class for objects subscribers. */
+  class Subscriber_
+  {
+    public:
+      virtual void callback(unsigned char *data)=0;
+      virtual int getEndpointType()=0;
+
+      // id_ is set by NodeHandle when we advertise 
+      int16_t id_;
+
+      virtual const char * getMsgType()=0;
+      virtual const char * getMsgMD5()=0;
+      const char * topic_;
+  };
+
+
+  /* Actual subscriber, templated on message type. */
   template<typename MsgT>
-  class Subscriber: public MsgReceiver{
+  class Subscriber: public Subscriber_{
     public:
       typedef void(*CallbackT)(const MsgT&);
       MsgT msg;
 
-      Subscriber(const char * topic_name, CallbackT msgCB){
+      Subscriber(const char * topic_name, CallbackT cb, int endpoint=rosserial_msgs::TopicInfo::ID_SUBSCRIBER) :
+        cb_(cb),
+        endpoint_(endpoint)
+      {
         topic_ = topic_name;
-        cb_= msgCB;
-      }
+      };
 
-      virtual void receive(unsigned char* data){
+      virtual void callback(unsigned char* data){
         msg.deserialize(data);
         this->cb_(msg);
       }
 
-      virtual const char * getMsgType(){return this->msg.getType();}
-      virtual int _getType(){return TOPIC_SUBSCRIBERS;}
+      virtual const char * getMsgType(){ return this->msg.getType(); }
+      virtual const char * getMsgMD5(){ return this->msg.getMD5(); }
+      virtual int getEndpointType(){ return endpoint_; }
 
     private:
       CallbackT cb_;
+      int endpoint_;
   };
 
 }
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/roscpp/Empty.h	Sat Nov 12 23:54:45 2011 +0000
@@ -0,0 +1,62 @@
+#ifndef _ROS_SERVICE_Empty_h
+#define _ROS_SERVICE_Empty_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace roscpp
+{
+
+static const char EMPTY[] = "roscpp/Empty";
+
+  class EmptyRequest : public ros::Msg
+  {
+    public:
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    virtual const char * getType(){ return EMPTY; };
+    virtual const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class EmptyResponse : public ros::Msg
+  {
+    public:
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    virtual const char * getType(){ return EMPTY; };
+    virtual const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class Empty {
+    public:
+    typedef EmptyRequest Request;
+    typedef EmptyResponse Response;
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/roscpp/GetLoggers.h	Sat Nov 12 23:54:45 2011 +0000
@@ -0,0 +1,82 @@
+#ifndef _ROS_SERVICE_GetLoggers_h
+#define _ROS_SERVICE_GetLoggers_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "roscpp/Logger.h"
+
+namespace roscpp
+{
+
+static const char GETLOGGERS[] = "roscpp/GetLoggers";
+
+  class GetLoggersRequest : public ros::Msg
+  {
+    public:
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    virtual const char * getType(){ return GETLOGGERS; };
+    virtual const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class GetLoggersResponse : public ros::Msg
+  {
+    public:
+      uint8_t loggers_length;
+      roscpp::Logger st_loggers;
+      roscpp::Logger * loggers;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = loggers_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < loggers_length; i++){
+      offset += this->loggers[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t loggers_lengthT = *(inbuffer + offset++);
+      if(loggers_lengthT > loggers_length)
+        this->loggers = (roscpp::Logger*)realloc(this->loggers, loggers_lengthT * sizeof(roscpp::Logger));
+      offset += 3;
+      loggers_length = loggers_lengthT;
+      for( uint8_t i = 0; i < loggers_length; i++){
+      offset += this->st_loggers.deserialize(inbuffer + offset);
+        memcpy( &(this->loggers[i]), &(this->st_loggers), sizeof(roscpp::Logger));
+      }
+     return offset;
+    }
+
+    virtual const char * getType(){ return GETLOGGERS; };
+    virtual const char * getMD5(){ return "32e97e85527d4678a8f9279894bb64b0"; };
+
+  };
+
+  class GetLoggers {
+    public:
+    typedef GetLoggersRequest Request;
+    typedef GetLoggersResponse Response;
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/roscpp/Logger.h	Sat Nov 12 23:54:45 2011 +0000
@@ -0,0 +1,62 @@
+#ifndef _ROS_roscpp_Logger_h
+#define _ROS_roscpp_Logger_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace roscpp
+{
+
+  class Logger : public ros::Msg
+  {
+    public:
+      char * name;
+      char * level;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t * length_name = (uint32_t *)(outbuffer + offset);
+      *length_name = strlen( (const char*) this->name);
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, *length_name);
+      offset += *length_name;
+      uint32_t * length_level = (uint32_t *)(outbuffer + offset);
+      *length_level = strlen( (const char*) this->level);
+      offset += 4;
+      memcpy(outbuffer + offset, this->level, *length_level);
+      offset += *length_level;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_name = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+      uint32_t length_level = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_level; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_level-1]=0;
+      this->level = (char *)(inbuffer + offset-1);
+      offset += length_level;
+     return offset;
+    }
+
+    virtual const char * getType(){ return "roscpp/Logger"; };
+    virtual const char * getMD5(){ return "a6069a2ff40db7bd32143dd66e1f408e"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/roscpp/SetLoggerLevel.h	Sat Nov 12 23:54:45 2011 +0000
@@ -0,0 +1,90 @@
+#ifndef _ROS_SERVICE_SetLoggerLevel_h
+#define _ROS_SERVICE_SetLoggerLevel_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace roscpp
+{
+
+static const char SETLOGGERLEVEL[] = "roscpp/SetLoggerLevel";
+
+  class SetLoggerLevelRequest : public ros::Msg
+  {
+    public:
+      char * logger;
+      char * level;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t * length_logger = (uint32_t *)(outbuffer + offset);
+      *length_logger = strlen( (const char*) this->logger);
+      offset += 4;
+      memcpy(outbuffer + offset, this->logger, *length_logger);
+      offset += *length_logger;
+      uint32_t * length_level = (uint32_t *)(outbuffer + offset);
+      *length_level = strlen( (const char*) this->level);
+      offset += 4;
+      memcpy(outbuffer + offset, this->level, *length_level);
+      offset += *length_level;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_logger = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_logger; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_logger-1]=0;
+      this->logger = (char *)(inbuffer + offset-1);
+      offset += length_logger;
+      uint32_t length_level = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_level; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_level-1]=0;
+      this->level = (char *)(inbuffer + offset-1);
+      offset += length_level;
+     return offset;
+    }
+
+    virtual const char * getType(){ return SETLOGGERLEVEL; };
+    virtual const char * getMD5(){ return "51da076440d78ca1684d36c868df61ea"; };
+
+  };
+
+  class SetLoggerLevelResponse : public ros::Msg
+  {
+    public:
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    virtual const char * getType(){ return SETLOGGERLEVEL; };
+    virtual const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class SetLoggerLevel {
+    public:
+    typedef SetLoggerLevelRequest Request;
+    typedef SetLoggerLevelResponse Response;
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosgraph_msgs/Clock.h	Sat Nov 12 23:54:45 2011 +0000
@@ -0,0 +1,56 @@
+#ifndef _ROS_rosgraph_msgs_Clock_h
+#define _ROS_rosgraph_msgs_Clock_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "ros/time.h"
+
+namespace rosgraph_msgs
+{
+
+  class Clock : public ros::Msg
+  {
+    public:
+      ros::Time clock;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->clock.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->clock.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->clock.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->clock.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->clock.sec);
+      *(outbuffer + offset + 0) = (this->clock.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->clock.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->clock.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->clock.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->clock.nsec);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->clock.sec |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->clock.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->clock.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->clock.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->clock.sec);
+      this->clock.nsec |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->clock.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->clock.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->clock.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->clock.nsec);
+     return offset;
+    }
+
+    virtual const char * getType(){ return "rosgraph_msgs/Clock"; };
+    virtual const char * getMD5(){ return "a9c97c1d230cfc112e270351a944ee47"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosgraph_msgs/Log.h	Sat Nov 12 23:54:45 2011 +0000
@@ -0,0 +1,144 @@
+#ifndef _ROS_rosgraph_msgs_Log_h
+#define _ROS_rosgraph_msgs_Log_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/Header.h"
+#include "rosgraph_msgs/byte.h"
+
+namespace rosgraph_msgs
+{
+
+  class Log : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      rosgraph_msgs::byte level;
+      char * name;
+      char * msg;
+      char * file;
+      char * function;
+      uint32_t line;
+      uint8_t topics_length;
+      char* st_topics;
+      char* * topics;
+      enum { DEBUG = 1  };
+      enum { INFO = 2   };
+      enum { WARN = 4   };
+      enum { ERROR = 8  };
+      enum { FATAL = 16  };
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->level.serialize(outbuffer + offset);
+      uint32_t * length_name = (uint32_t *)(outbuffer + offset);
+      *length_name = strlen( (const char*) this->name);
+      offset += 4;
+      memcpy(outbuffer + offset, this->name, *length_name);
+      offset += *length_name;
+      uint32_t * length_msg = (uint32_t *)(outbuffer + offset);
+      *length_msg = strlen( (const char*) this->msg);
+      offset += 4;
+      memcpy(outbuffer + offset, this->msg, *length_msg);
+      offset += *length_msg;
+      uint32_t * length_file = (uint32_t *)(outbuffer + offset);
+      *length_file = strlen( (const char*) this->file);
+      offset += 4;
+      memcpy(outbuffer + offset, this->file, *length_file);
+      offset += *length_file;
+      uint32_t * length_function = (uint32_t *)(outbuffer + offset);
+      *length_function = strlen( (const char*) this->function);
+      offset += 4;
+      memcpy(outbuffer + offset, this->function, *length_function);
+      offset += *length_function;
+      *(outbuffer + offset + 0) = (this->line >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->line >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->line >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->line >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->line);
+      *(outbuffer + offset++) = topics_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < topics_length; i++){
+      uint32_t * length_topicsi = (uint32_t *)(outbuffer + offset);
+      *length_topicsi = strlen( (const char*) this->topics[i]);
+      offset += 4;
+      memcpy(outbuffer + offset, this->topics[i], *length_topicsi);
+      offset += *length_topicsi;
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->level.deserialize(inbuffer + offset);
+      uint32_t length_name = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+      uint32_t length_msg = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_msg; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_msg-1]=0;
+      this->msg = (char *)(inbuffer + offset-1);
+      offset += length_msg;
+      uint32_t length_file = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_file; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_file-1]=0;
+      this->file = (char *)(inbuffer + offset-1);
+      offset += length_file;
+      uint32_t length_function = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_function; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_function-1]=0;
+      this->function = (char *)(inbuffer + offset-1);
+      offset += length_function;
+      this->line |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->line |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->line |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->line |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->line);
+      uint8_t topics_lengthT = *(inbuffer + offset++);
+      if(topics_lengthT > topics_length)
+        this->topics = (char**)realloc(this->topics, topics_lengthT * sizeof(char*));
+      offset += 3;
+      topics_length = topics_lengthT;
+      for( uint8_t i = 0; i < topics_length; i++){
+      uint32_t length_st_topics = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_topics; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_topics-1]=0;
+      this->st_topics = (char *)(inbuffer + offset-1);
+      offset += length_st_topics;
+        memcpy( &(this->topics[i]), &(this->st_topics), sizeof(char*));
+      }
+     return offset;
+    }
+
+    virtual const char * getType(){ return "rosgraph_msgs/Log"; };
+    virtual const char * getMD5(){ return "acffd30cd6b6de30f120938c17c593fb"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- a/rosserial_mbed/Adc.h	Sun Oct 16 09:35:11 2011 +0000
+++ /dev/null	Thu Jan 01 00:00:00 1970 +0000
@@ -1,141 +0,0 @@
-#ifndef ros_Adc_h
-#define ros_Adc_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-
-namespace rosserial_mbed
-{
-
-  class Adc : public ros::Msg
-  {
-    public:
-      unsigned short adc0;
-      unsigned short adc1;
-      unsigned short adc2;
-      unsigned short adc3;
-      unsigned short adc4;
-      unsigned short adc5;
-
-    virtual int serialize(unsigned char *outbuffer)
-    {
-      int offset = 0;
-      union {
-        unsigned short real;
-        unsigned short base;
-      } u_adc0;
-      u_adc0.real = this->adc0;
-      *(outbuffer + offset + 0) = (u_adc0.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_adc0.base >> (8 * 1)) & 0xFF;
-      offset += sizeof(this->adc0);
-      union {
-        unsigned short real;
-        unsigned short base;
-      } u_adc1;
-      u_adc1.real = this->adc1;
-      *(outbuffer + offset + 0) = (u_adc1.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_adc1.base >> (8 * 1)) & 0xFF;
-      offset += sizeof(this->adc1);
-      union {
-        unsigned short real;
-        unsigned short base;
-      } u_adc2;
-      u_adc2.real = this->adc2;
-      *(outbuffer + offset + 0) = (u_adc2.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_adc2.base >> (8 * 1)) & 0xFF;
-      offset += sizeof(this->adc2);
-      union {
-        unsigned short real;
-        unsigned short base;
-      } u_adc3;
-      u_adc3.real = this->adc3;
-      *(outbuffer + offset + 0) = (u_adc3.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_adc3.base >> (8 * 1)) & 0xFF;
-      offset += sizeof(this->adc3);
-      union {
-        unsigned short real;
-        unsigned short base;
-      } u_adc4;
-      u_adc4.real = this->adc4;
-      *(outbuffer + offset + 0) = (u_adc4.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_adc4.base >> (8 * 1)) & 0xFF;
-      offset += sizeof(this->adc4);
-      union {
-        unsigned short real;
-        unsigned short base;
-      } u_adc5;
-      u_adc5.real = this->adc5;
-      *(outbuffer + offset + 0) = (u_adc5.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_adc5.base >> (8 * 1)) & 0xFF;
-      offset += sizeof(this->adc5);
-      return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer)
-    {
-      int offset = 0;
-      union {
-        unsigned short real;
-        unsigned short base;
-      } u_adc0;
-      u_adc0.base = 0;
-      u_adc0.base |= ((typeof(u_adc0.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_adc0.base |= ((typeof(u_adc0.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      this->adc0 = u_adc0.real;
-      offset += sizeof(this->adc0);
-      union {
-        unsigned short real;
-        unsigned short base;
-      } u_adc1;
-      u_adc1.base = 0;
-      u_adc1.base |= ((typeof(u_adc1.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_adc1.base |= ((typeof(u_adc1.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      this->adc1 = u_adc1.real;
-      offset += sizeof(this->adc1);
-      union {
-        unsigned short real;
-        unsigned short base;
-      } u_adc2;
-      u_adc2.base = 0;
-      u_adc2.base |= ((typeof(u_adc2.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_adc2.base |= ((typeof(u_adc2.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      this->adc2 = u_adc2.real;
-      offset += sizeof(this->adc2);
-      union {
-        unsigned short real;
-        unsigned short base;
-      } u_adc3;
-      u_adc3.base = 0;
-      u_adc3.base |= ((typeof(u_adc3.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_adc3.base |= ((typeof(u_adc3.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      this->adc3 = u_adc3.real;
-      offset += sizeof(this->adc3);
-      union {
-        unsigned short real;
-        unsigned short base;
-      } u_adc4;
-      u_adc4.base = 0;
-      u_adc4.base |= ((typeof(u_adc4.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_adc4.base |= ((typeof(u_adc4.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      this->adc4 = u_adc4.real;
-      offset += sizeof(this->adc4);
-      union {
-        unsigned short real;
-        unsigned short base;
-      } u_adc5;
-      u_adc5.base = 0;
-      u_adc5.base |= ((typeof(u_adc5.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_adc5.base |= ((typeof(u_adc5.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      this->adc5 = u_adc5.real;
-      offset += sizeof(this->adc5);
-     return offset;
-    }
-
-    virtual const char * getType(){ return "rosserial_mbed/Adc"; };
-
-  };
-
-}
-#endif
\ No newline at end of file
--- a/rosserial_msgs/Log.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/rosserial_msgs/Log.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_rosserial_msgs_Log_h
-#define ros_rosserial_msgs_Log_h
+#ifndef _ROS_rosserial_msgs_Log_h
+#define _ROS_rosserial_msgs_Log_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 
 namespace rosserial_msgs
 {
@@ -12,7 +12,7 @@
   class Log : public ros::Msg
   {
     public:
-      unsigned char level;
+      uint8_t level;
       char * msg;
       enum { DEBUG = 0 };
       enum { INFO = 1 };
@@ -20,17 +20,12 @@
       enum { ERROR = 3 };
       enum { FATAL = 4 };
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
-      union {
-        unsigned char real;
-        unsigned char base;
-      } u_level;
-      u_level.real = this->level;
-      *(outbuffer + offset + 0) = (u_level.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->level >> (8 * 0)) & 0xFF;
       offset += sizeof(this->level);
-      long * length_msg = (long *)(outbuffer + offset);
+      uint32_t * length_msg = (uint32_t *)(outbuffer + offset);
       *length_msg = strlen( (const char*) this->msg);
       offset += 4;
       memcpy(outbuffer + offset, this->msg, *length_msg);
@@ -41,19 +36,13 @@
     virtual int deserialize(unsigned char *inbuffer)
     {
       int offset = 0;
-      union {
-        unsigned char real;
-        unsigned char base;
-      } u_level;
-      u_level.base = 0;
-      u_level.base |= ((typeof(u_level.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      this->level = u_level.real;
+      this->level |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
       offset += sizeof(this->level);
       uint32_t length_msg = *(uint32_t *)(inbuffer + offset);
       offset += 4;
       for(unsigned int k= offset; k< offset+length_msg; ++k){
           inbuffer[k-1]=inbuffer[k];
-           }
+      }
       inbuffer[offset+length_msg-1]=0;
       this->msg = (char *)(inbuffer + offset-1);
       offset += length_msg;
@@ -61,6 +50,7 @@
     }
 
     virtual const char * getType(){ return "rosserial_msgs/Log"; };
+    virtual const char * getMD5(){ return "7170d5aec999754ba0d9f762bf49b913"; };
 
   };
 
--- a/rosserial_msgs/RequestParam.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/rosserial_msgs/RequestParam.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,9 +1,9 @@
-#ifndef ros_SERVICE_RequestParam_h
-#define ros_SERVICE_RequestParam_h
+#ifndef _ROS_SERVICE_RequestParam_h
+#define _ROS_SERVICE_RequestParam_h
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 
 namespace rosserial_msgs
 {
@@ -15,10 +15,10 @@
     public:
       char * name;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
-      long * length_name = (long *)(outbuffer + offset);
+      uint32_t * length_name = (uint32_t *)(outbuffer + offset);
       *length_name = strlen( (const char*) this->name);
       offset += 4;
       memcpy(outbuffer + offset, this->name, *length_name);
@@ -33,7 +33,7 @@
       offset += 4;
       for(unsigned int k= offset; k< offset+length_name; ++k){
           inbuffer[k-1]=inbuffer[k];
-           }
+      }
       inbuffer[offset+length_name-1]=0;
       this->name = (char *)(inbuffer + offset-1);
       offset += length_name;
@@ -41,33 +41,34 @@
     }
 
     virtual const char * getType(){ return REQUESTPARAM; };
+    virtual const char * getMD5(){ return "c1f3d28f1b044c871e6eff2e9fc3c667"; };
 
   };
 
   class RequestParamResponse : public ros::Msg
   {
     public:
-      unsigned char ints_length;
-      long st_ints;
-      long * ints;
-      unsigned char floats_length;
+      uint8_t ints_length;
+      int32_t st_ints;
+      int32_t * ints;
+      uint8_t floats_length;
       float st_floats;
       float * floats;
-      unsigned char strings_length;
+      uint8_t strings_length;
       char* st_strings;
       char* * strings;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       *(outbuffer + offset++) = ints_length;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < ints_length; i++){
+      for( uint8_t i = 0; i < ints_length; i++){
       union {
-        long real;
-        unsigned long base;
+        int32_t real;
+        uint32_t base;
       } u_intsi;
       u_intsi.real = this->ints[i];
       *(outbuffer + offset + 0) = (u_intsi.base >> (8 * 0)) & 0xFF;
@@ -80,10 +81,10 @@
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < floats_length; i++){
+      for( uint8_t i = 0; i < floats_length; i++){
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_floatsi;
       u_floatsi.real = this->floats[i];
       *(outbuffer + offset + 0) = (u_floatsi.base >> (8 * 0)) & 0xFF;
@@ -96,8 +97,8 @@
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < strings_length; i++){
-      long * length_stringsi = (long *)(outbuffer + offset);
+      for( uint8_t i = 0; i < strings_length; i++){
+      uint32_t * length_stringsi = (uint32_t *)(outbuffer + offset);
       *length_stringsi = strlen( (const char*) this->strings[i]);
       offset += 4;
       memcpy(outbuffer + offset, this->strings[i], *length_stringsi);
@@ -109,55 +110,55 @@
     virtual int deserialize(unsigned char *inbuffer)
     {
       int offset = 0;
-      unsigned char ints_lengthT = *(inbuffer + offset++);
+      uint8_t ints_lengthT = *(inbuffer + offset++);
       if(ints_lengthT > ints_length)
-        this->ints = (long*)realloc(this->ints, ints_lengthT * sizeof(long));
+        this->ints = (int32_t*)realloc(this->ints, ints_lengthT * sizeof(int32_t));
       offset += 3;
       ints_length = ints_lengthT;
-      for( unsigned char i = 0; i < ints_length; i++){
+      for( uint8_t i = 0; i < ints_length; i++){
       union {
-        long real;
-        unsigned long base;
+        int32_t real;
+        uint32_t base;
       } u_st_ints;
       u_st_ints.base = 0;
-      u_st_ints.base |= ((typeof(u_st_ints.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_st_ints.base |= ((typeof(u_st_ints.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_st_ints.base |= ((typeof(u_st_ints.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_st_ints.base |= ((typeof(u_st_ints.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_ints.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       this->st_ints = u_st_ints.real;
       offset += sizeof(this->st_ints);
-        memcpy( &(this->ints[i]), &(this->st_ints), sizeof(long));
+        memcpy( &(this->ints[i]), &(this->st_ints), sizeof(int32_t));
       }
-      unsigned char floats_lengthT = *(inbuffer + offset++);
+      uint8_t floats_lengthT = *(inbuffer + offset++);
       if(floats_lengthT > floats_length)
         this->floats = (float*)realloc(this->floats, floats_lengthT * sizeof(float));
       offset += 3;
       floats_length = floats_lengthT;
-      for( unsigned char i = 0; i < floats_length; i++){
+      for( uint8_t i = 0; i < floats_length; i++){
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_st_floats;
       u_st_floats.base = 0;
-      u_st_floats.base |= ((typeof(u_st_floats.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_st_floats.base |= ((typeof(u_st_floats.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_st_floats.base |= ((typeof(u_st_floats.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_st_floats.base |= ((typeof(u_st_floats.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_floats.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       this->st_floats = u_st_floats.real;
       offset += sizeof(this->st_floats);
         memcpy( &(this->floats[i]), &(this->st_floats), sizeof(float));
       }
-      unsigned char strings_lengthT = *(inbuffer + offset++);
+      uint8_t strings_lengthT = *(inbuffer + offset++);
       if(strings_lengthT > strings_length)
         this->strings = (char**)realloc(this->strings, strings_lengthT * sizeof(char*));
       offset += 3;
       strings_length = strings_lengthT;
-      for( unsigned char i = 0; i < strings_length; i++){
+      for( uint8_t i = 0; i < strings_length; i++){
       uint32_t length_st_strings = *(uint32_t *)(inbuffer + offset);
       offset += 4;
       for(unsigned int k= offset; k< offset+length_st_strings; ++k){
           inbuffer[k-1]=inbuffer[k];
-           }
+      }
       inbuffer[offset+length_st_strings-1]=0;
       this->st_strings = (char *)(inbuffer + offset-1);
       offset += length_st_strings;
@@ -166,8 +167,15 @@
      return offset;
     }
 
-   virtual const char * getType(){ return REQUESTPARAM; };
+    virtual const char * getType(){ return REQUESTPARAM; };
+    virtual const char * getMD5(){ return "9f0e98bda65981986ddf53afa7a40e49"; };
+
+  };
 
+  class RequestParam {
+    public:
+    typedef RequestParamRequest Request;
+    typedef RequestParamResponse Response;
   };
 
 }
--- a/rosserial_msgs/TopicInfo.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/rosserial_msgs/TopicInfo.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,77 +1,75 @@
-#ifndef ros_rosserial_msgs_TopicInfo_h
-#define ros_rosserial_msgs_TopicInfo_h
+#ifndef _ROS_rosserial_msgs_TopicInfo_h
+#define _ROS_rosserial_msgs_TopicInfo_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
+
 namespace rosserial_msgs
 {
+
   class TopicInfo : public ros::Msg
   {
     public:
-      unsigned short topic_id;
+      uint16_t topic_id;
       char * topic_name;
       char * message_type;
-      char * md5_checksum;
+      char * md5sum;
+      int32_t buffer_size;
       enum { ID_PUBLISHER = 0 };
       enum { ID_SUBSCRIBER = 1 };
       enum { ID_SERVICE_SERVER = 2 };
-      enum { ID_SERVICE_CLIENT = 3 };
-      enum { ID_PARAMETER_REQUEST = 4 };
-      enum { ID_LOG = 5 };
+      enum { ID_SERVICE_CLIENT = 4 };
+      enum { ID_PARAMETER_REQUEST = 6 };
+      enum { ID_LOG = 7 };
       enum { ID_TIME = 10 };
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
-      union {
-        uint16_t real;
-        uint16_t base;
-      } u_topic_id;
-      u_topic_id.real = this->topic_id;
-      *(outbuffer + offset + 0) = (u_topic_id.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_topic_id.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->topic_id >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->topic_id >> (8 * 1)) & 0xFF;
       offset += sizeof(this->topic_id);
-      
-      long * length_topic_name = (long *)(outbuffer + offset);
+      uint32_t * length_topic_name = (uint32_t *)(outbuffer + offset);
       *length_topic_name = strlen( (const char*) this->topic_name);
       offset += 4;
       memcpy(outbuffer + offset, this->topic_name, *length_topic_name);
       offset += *length_topic_name;
-      
-      long * length_message_type = (long *)(outbuffer + offset);
+      uint32_t * length_message_type = (uint32_t *)(outbuffer + offset);
       *length_message_type = strlen( (const char*) this->message_type);
       offset += 4;
       memcpy(outbuffer + offset, this->message_type, *length_message_type);
       offset += *length_message_type;
-
-      long * length_md5_checksum = (long *)(outbuffer + offset);
-      *length_md5_checksum = strlen( (const char*) this->md5_checksum);
+      uint32_t * length_md5sum = (uint32_t *)(outbuffer + offset);
+      *length_md5sum = strlen( (const char*) this->md5sum);
       offset += 4;
-      memcpy(outbuffer + offset, this->md5_checksum, *length_md5_checksum);
-      offset += *length_md5_checksum;
-      
+      memcpy(outbuffer + offset, this->md5sum, *length_md5sum);
+      offset += *length_md5sum;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_buffer_size;
+      u_buffer_size.real = this->buffer_size;
+      *(outbuffer + offset + 0) = (u_buffer_size.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_buffer_size.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_buffer_size.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_buffer_size.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->buffer_size);
       return offset;
     }
 
     virtual int deserialize(unsigned char *inbuffer)
     {
       int offset = 0;
-      union {
-        unsigned short real;
-        unsigned short base;
-      } u_topic_id;
-      u_topic_id.base = 0;
-      u_topic_id.base |= ((typeof(u_topic_id.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_topic_id.base |= ((typeof(u_topic_id.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      this->topic_id = u_topic_id.real;
+      this->topic_id |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->topic_id |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
       offset += sizeof(this->topic_id);
       uint32_t length_topic_name = *(uint32_t *)(inbuffer + offset);
       offset += 4;
       for(unsigned int k= offset; k< offset+length_topic_name; ++k){
           inbuffer[k-1]=inbuffer[k];
-           }
+      }
       inbuffer[offset+length_topic_name-1]=0;
       this->topic_name = (char *)(inbuffer + offset-1);
       offset += length_topic_name;
@@ -79,24 +77,34 @@
       offset += 4;
       for(unsigned int k= offset; k< offset+length_message_type; ++k){
           inbuffer[k-1]=inbuffer[k];
-           }
+      }
       inbuffer[offset+length_message_type-1]=0;
       this->message_type = (char *)(inbuffer + offset-1);
       offset += length_message_type;
-
-      uint32_t length_md5_checksum = *(uint32_t *)(inbuffer + offset);
+      uint32_t length_md5sum = *(uint32_t *)(inbuffer + offset);
       offset += 4;
-      for(unsigned int k= offset; k< offset+length_md5_checksum; ++k){
+      for(unsigned int k= offset; k< offset+length_md5sum; ++k){
           inbuffer[k-1]=inbuffer[k];
-           }
-      inbuffer[offset+length_md5_checksum-1]=0;
-      this->md5_checksum = (char *)(inbuffer + offset-1);
-      offset += length_md5_checksum;
-
+      }
+      inbuffer[offset+length_md5sum-1]=0;
+      this->md5sum = (char *)(inbuffer + offset-1);
+      offset += length_md5sum;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_buffer_size;
+      u_buffer_size.base = 0;
+      u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->buffer_size = u_buffer_size.real;
+      offset += sizeof(this->buffer_size);
      return offset;
     }
 
     virtual const char * getType(){ return "rosserial_msgs/TopicInfo"; };
+    virtual const char * getMD5(){ return "63aa5e8f1bdd6f35c69fe1a1b9d28e9f"; };
 
   };
 
--- a/sensor_msgs/CameraInfo.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/sensor_msgs/CameraInfo.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_CameraInfo_h
-#define ros_CameraInfo_h
+#ifndef _ROS_sensor_msgs_CameraInfo_h
+#define _ROS_sensor_msgs_CameraInfo_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "std_msgs/Header.h"
 #include "sensor_msgs/RegionOfInterest.h"
 
@@ -15,44 +15,34 @@
   {
     public:
       std_msgs::Header header;
-      unsigned long height;
-      unsigned long width;
+      uint32_t height;
+      uint32_t width;
       char * distortion_model;
-      unsigned char D_length;
+      uint8_t D_length;
       float st_D;
       float * D;
       float K[9];
       float R[9];
       float P[12];
-      unsigned long binning_x;
-      unsigned long binning_y;
+      uint32_t binning_x;
+      uint32_t binning_y;
       sensor_msgs::RegionOfInterest roi;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->header.serialize(outbuffer + offset);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_height;
-      u_height.real = this->height;
-      *(outbuffer + offset + 0) = (u_height.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_height.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_height.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_height.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF;
       offset += sizeof(this->height);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_width;
-      u_width.real = this->width;
-      *(outbuffer + offset + 0) = (u_width.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_width.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_width.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_width.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF;
       offset += sizeof(this->width);
-      long * length_distortion_model = (long *)(outbuffer + offset);
+      uint32_t * length_distortion_model = (uint32_t *)(outbuffer + offset);
       *length_distortion_model = strlen( (const char*) this->distortion_model);
       offset += 4;
       memcpy(outbuffer + offset, this->distortion_model, *length_distortion_model);
@@ -61,12 +51,12 @@
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < D_length; i++){
-      long * val_Di = (long *) &(this->D[i]);
-      long exp_Di = (((*val_Di)>>23)&255);
+      for( uint8_t i = 0; i < D_length; i++){
+      int32_t * val_Di = (long *) &(this->D[i]);
+      int32_t exp_Di = (((*val_Di)>>23)&255);
       if(exp_Di != 0)
         exp_Di += 1023-127;
-      long sig_Di = *val_Di;
+      int32_t sig_Di = *val_Di;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
@@ -78,12 +68,12 @@
       if(this->D[i] < 0) *(outbuffer + offset -1) |= 0x80;
       }
       unsigned char * K_val = (unsigned char *) this->K;
-      for( unsigned char i = 0; i < 9; i++){
-      long * val_Ki = (long *) &(this->K[i]);
-      long exp_Ki = (((*val_Ki)>>23)&255);
+      for( uint8_t i = 0; i < 9; i++){
+      int32_t * val_Ki = (long *) &(this->K[i]);
+      int32_t exp_Ki = (((*val_Ki)>>23)&255);
       if(exp_Ki != 0)
         exp_Ki += 1023-127;
-      long sig_Ki = *val_Ki;
+      int32_t sig_Ki = *val_Ki;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
@@ -95,12 +85,12 @@
       if(this->K[i] < 0) *(outbuffer + offset -1) |= 0x80;
       }
       unsigned char * R_val = (unsigned char *) this->R;
-      for( unsigned char i = 0; i < 9; i++){
-      long * val_Ri = (long *) &(this->R[i]);
-      long exp_Ri = (((*val_Ri)>>23)&255);
+      for( uint8_t i = 0; i < 9; i++){
+      int32_t * val_Ri = (long *) &(this->R[i]);
+      int32_t exp_Ri = (((*val_Ri)>>23)&255);
       if(exp_Ri != 0)
         exp_Ri += 1023-127;
-      long sig_Ri = *val_Ri;
+      int32_t sig_Ri = *val_Ri;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
@@ -112,12 +102,12 @@
       if(this->R[i] < 0) *(outbuffer + offset -1) |= 0x80;
       }
       unsigned char * P_val = (unsigned char *) this->P;
-      for( unsigned char i = 0; i < 12; i++){
-      long * val_Pi = (long *) &(this->P[i]);
-      long exp_Pi = (((*val_Pi)>>23)&255);
+      for( uint8_t i = 0; i < 12; i++){
+      int32_t * val_Pi = (long *) &(this->P[i]);
+      int32_t exp_Pi = (((*val_Pi)>>23)&255);
       if(exp_Pi != 0)
         exp_Pi += 1023-127;
-      long sig_Pi = *val_Pi;
+      int32_t sig_Pi = *val_Pi;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
@@ -128,25 +118,15 @@
       *(outbuffer + offset++) = (exp_Pi>>4) & 0x7F;
       if(this->P[i] < 0) *(outbuffer + offset -1) |= 0x80;
       }
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_binning_x;
-      u_binning_x.real = this->binning_x;
-      *(outbuffer + offset + 0) = (u_binning_x.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_binning_x.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_binning_x.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_binning_x.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->binning_x >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->binning_x >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->binning_x >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->binning_x >> (8 * 3)) & 0xFF;
       offset += sizeof(this->binning_x);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_binning_y;
-      u_binning_y.real = this->binning_y;
-      *(outbuffer + offset + 0) = (u_binning_y.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_binning_y.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_binning_y.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_binning_y.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->binning_y >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->binning_y >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->binning_y >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->binning_y >> (8 * 3)) & 0xFF;
       offset += sizeof(this->binning_y);
       offset += this->roi.serialize(outbuffer + offset);
       return offset;
@@ -156,124 +136,101 @@
     {
       int offset = 0;
       offset += this->header.deserialize(inbuffer + offset);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_height;
-      u_height.base = 0;
-      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->height = u_height.real;
+      this->height |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       offset += sizeof(this->height);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_width;
-      u_width.base = 0;
-      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->width = u_width.real;
+      this->width |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       offset += sizeof(this->width);
       uint32_t length_distortion_model = *(uint32_t *)(inbuffer + offset);
       offset += 4;
       for(unsigned int k= offset; k< offset+length_distortion_model; ++k){
           inbuffer[k-1]=inbuffer[k];
-           }
+      }
       inbuffer[offset+length_distortion_model-1]=0;
       this->distortion_model = (char *)(inbuffer + offset-1);
       offset += length_distortion_model;
-      unsigned char D_lengthT = *(inbuffer + offset++);
+      uint8_t D_lengthT = *(inbuffer + offset++);
       if(D_lengthT > D_length)
         this->D = (float*)realloc(this->D, D_lengthT * sizeof(float));
       offset += 3;
       D_length = D_lengthT;
-      for( unsigned char i = 0; i < D_length; i++){
-      unsigned long * val_st_D = (unsigned long*) &(this->st_D);
+      for( uint8_t i = 0; i < D_length; i++){
+      uint32_t * val_st_D = (uint32_t*) &(this->st_D);
       offset += 3;
-      *val_st_D = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-      *val_st_D |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-      *val_st_D |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-      *val_st_D |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-      unsigned long exp_st_D = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-      exp_st_D |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      *val_st_D = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_st_D |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_st_D |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_st_D |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_st_D = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_st_D |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
       if(exp_st_D !=0)
         *val_st_D |= ((exp_st_D)-1023+127)<<23;
       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->st_D = -this->st_D;
         memcpy( &(this->D[i]), &(this->st_D), sizeof(float));
       }
-      unsigned char * K_val = (unsigned char *) this->K;
-      for( unsigned char i = 0; i < 9; i++){
-      unsigned long * val_Ki = (unsigned long*) &(this->K[i]);
+      uint8_t * K_val = (uint8_t*) this->K;
+      for( uint8_t i = 0; i < 9; i++){
+      uint32_t * val_Ki = (uint32_t*) &(this->K[i]);
       offset += 3;
-      *val_Ki = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-      *val_Ki |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-      *val_Ki |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-      *val_Ki |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-      unsigned long exp_Ki = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-      exp_Ki |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      *val_Ki = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_Ki |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_Ki |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_Ki |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_Ki = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_Ki |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
       if(exp_Ki !=0)
         *val_Ki |= ((exp_Ki)-1023+127)<<23;
       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->K[i] = -this->K[i];
       }
-      unsigned char * R_val = (unsigned char *) this->R;
-      for( unsigned char i = 0; i < 9; i++){
-      unsigned long * val_Ri = (unsigned long*) &(this->R[i]);
+      uint8_t * R_val = (uint8_t*) this->R;
+      for( uint8_t i = 0; i < 9; i++){
+      uint32_t * val_Ri = (uint32_t*) &(this->R[i]);
       offset += 3;
-      *val_Ri = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-      *val_Ri |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-      *val_Ri |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-      *val_Ri |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-      unsigned long exp_Ri = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-      exp_Ri |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      *val_Ri = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_Ri |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_Ri |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_Ri |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_Ri = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_Ri |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
       if(exp_Ri !=0)
         *val_Ri |= ((exp_Ri)-1023+127)<<23;
       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->R[i] = -this->R[i];
       }
-      unsigned char * P_val = (unsigned char *) this->P;
-      for( unsigned char i = 0; i < 12; i++){
-      unsigned long * val_Pi = (unsigned long*) &(this->P[i]);
+      uint8_t * P_val = (uint8_t*) this->P;
+      for( uint8_t i = 0; i < 12; i++){
+      uint32_t * val_Pi = (uint32_t*) &(this->P[i]);
       offset += 3;
-      *val_Pi = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-      *val_Pi |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-      *val_Pi |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-      *val_Pi |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-      unsigned long exp_Pi = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-      exp_Pi |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      *val_Pi = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_Pi |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_Pi |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_Pi |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_Pi = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_Pi |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
       if(exp_Pi !=0)
         *val_Pi |= ((exp_Pi)-1023+127)<<23;
       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->P[i] = -this->P[i];
       }
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_binning_x;
-      u_binning_x.base = 0;
-      u_binning_x.base |= ((typeof(u_binning_x.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_binning_x.base |= ((typeof(u_binning_x.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_binning_x.base |= ((typeof(u_binning_x.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_binning_x.base |= ((typeof(u_binning_x.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->binning_x = u_binning_x.real;
+      this->binning_x |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->binning_x |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->binning_x |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->binning_x |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       offset += sizeof(this->binning_x);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_binning_y;
-      u_binning_y.base = 0;
-      u_binning_y.base |= ((typeof(u_binning_y.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_binning_y.base |= ((typeof(u_binning_y.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_binning_y.base |= ((typeof(u_binning_y.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_binning_y.base |= ((typeof(u_binning_y.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->binning_y = u_binning_y.real;
+      this->binning_y |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->binning_y |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->binning_y |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->binning_y |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       offset += sizeof(this->binning_y);
       offset += this->roi.deserialize(inbuffer + offset);
      return offset;
     }
 
-   virtual const char * getType(){ return "sensor_msgs/CameraInfo"; };
+    virtual const char * getType(){ return "sensor_msgs/CameraInfo"; };
+    virtual const char * getMD5(){ return "c9a58c1b0b154e0e6da7578cb991d214"; };
 
   };
 
--- a/sensor_msgs/ChannelFloat32.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/sensor_msgs/ChannelFloat32.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_ChannelFloat32_h
-#define ros_ChannelFloat32_h
+  #ifndef _ROS_sensor_msgs_ChannelFloat32_h
+#define _ROS_sensor_msgs_ChannelFloat32_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 
 namespace sensor_msgs
 {
@@ -13,14 +13,14 @@
   {
     public:
       char * name;
-      unsigned char values_length;
+      uint8_t values_length;
       float st_values;
       float * values;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
-      long * length_name = (long *)(outbuffer + offset);
+      uint32_t * length_name = (uint32_t *)(outbuffer + offset);
       *length_name = strlen( (const char*) this->name);
       offset += 4;
       memcpy(outbuffer + offset, this->name, *length_name);
@@ -29,10 +29,10 @@
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < values_length; i++){
+      for( uint8_t i = 0; i < values_length; i++){
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_valuesi;
       u_valuesi.real = this->values[i];
       *(outbuffer + offset + 0) = (u_valuesi.base >> (8 * 0)) & 0xFF;
@@ -51,25 +51,25 @@
       offset += 4;
       for(unsigned int k= offset; k< offset+length_name; ++k){
           inbuffer[k-1]=inbuffer[k];
-           }
+      }
       inbuffer[offset+length_name-1]=0;
       this->name = (char *)(inbuffer + offset-1);
       offset += length_name;
-      unsigned char values_lengthT = *(inbuffer + offset++);
+      uint8_t values_lengthT = *(inbuffer + offset++);
       if(values_lengthT > values_length)
         this->values = (float*)realloc(this->values, values_lengthT * sizeof(float));
       offset += 3;
       values_length = values_lengthT;
-      for( unsigned char i = 0; i < values_length; i++){
+      for( uint8_t i = 0; i < values_length; i++){
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_st_values;
       u_st_values.base = 0;
-      u_st_values.base |= ((typeof(u_st_values.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_st_values.base |= ((typeof(u_st_values.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_st_values.base |= ((typeof(u_st_values.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_st_values.base |= ((typeof(u_st_values.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_values.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       this->st_values = u_st_values.real;
       offset += sizeof(this->st_values);
         memcpy( &(this->values[i]), &(this->st_values), sizeof(float));
@@ -77,7 +77,8 @@
      return offset;
     }
 
-   virtual const char * getType(){ return "sensor_msgs/ChannelFloat32"; };
+    virtual const char * getType(){ return "sensor_msgs/ChannelFloat32"; };
+    virtual const char * getMD5(){ return "3d40139cdd33dfedcb71ffeeeb42ae7f"; };
 
   };
 
--- a/sensor_msgs/CompressedImage.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/sensor_msgs/CompressedImage.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_CompressedImage_h
-#define ros_CompressedImage_h
+#ifndef _ROS_sensor_msgs_CompressedImage_h
+#define _ROS_sensor_msgs_CompressedImage_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "std_msgs/Header.h"
 
 namespace sensor_msgs
@@ -15,15 +15,15 @@
     public:
       std_msgs::Header header;
       char * format;
-      unsigned char data_length;
-      unsigned char st_data;
-      unsigned char * data;
+      uint8_t data_length;
+      uint8_t st_data;
+      uint8_t * data;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->header.serialize(outbuffer + offset);
-      long * length_format = (long *)(outbuffer + offset);
+      uint32_t * length_format = (uint32_t *)(outbuffer + offset);
       *length_format = strlen( (const char*) this->format);
       offset += 4;
       memcpy(outbuffer + offset, this->format, *length_format);
@@ -32,13 +32,8 @@
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < data_length; i++){
-      union {
-        unsigned char real;
-        unsigned char base;
-      } u_datai;
-      u_datai.real = this->data[i];
-      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+      for( uint8_t i = 0; i < data_length; i++){
+      *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF;
       offset += sizeof(this->data[i]);
       }
       return offset;
@@ -52,30 +47,25 @@
       offset += 4;
       for(unsigned int k= offset; k< offset+length_format; ++k){
           inbuffer[k-1]=inbuffer[k];
-           }
+      }
       inbuffer[offset+length_format-1]=0;
       this->format = (char *)(inbuffer + offset-1);
       offset += length_format;
-      unsigned char data_lengthT = *(inbuffer + offset++);
+      uint8_t data_lengthT = *(inbuffer + offset++);
       if(data_lengthT > data_length)
-        this->data = (unsigned char*)realloc(this->data, data_lengthT * sizeof(unsigned char));
+        this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t));
       offset += 3;
       data_length = data_lengthT;
-      for( unsigned char i = 0; i < data_length; i++){
-      union {
-        unsigned char real;
-        unsigned char base;
-      } u_st_data;
-      u_st_data.base = 0;
-      u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      this->st_data = u_st_data.real;
+      for( uint8_t i = 0; i < data_length; i++){
+      this->st_data |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
       offset += sizeof(this->st_data);
-        memcpy( &(this->data[i]), &(this->st_data), sizeof(unsigned char));
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t));
       }
      return offset;
     }
 
-   virtual const char * getType(){ return "sensor_msgs/CompressedImage"; };
+    virtual const char * getType(){ return "sensor_msgs/CompressedImage"; };
+    virtual const char * getMD5(){ return "8f7a12909da2c9d3332d540a0977563f"; };
 
   };
 
--- a/sensor_msgs/Image.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/sensor_msgs/Image.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_Image_h
-#define ros_Image_h
+#ifndef _ROS_sensor_msgs_Image_h
+#define _ROS_sensor_msgs_Image_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "std_msgs/Header.h"
 
 namespace sensor_msgs
@@ -14,72 +14,47 @@
   {
     public:
       std_msgs::Header header;
-      unsigned long height;
-      unsigned long width;
+      uint32_t height;
+      uint32_t width;
       char * encoding;
-      unsigned char is_bigendian;
-      unsigned long step;
-      unsigned char data_length;
-      unsigned char st_data;
-      unsigned char * data;
+      uint8_t is_bigendian;
+      uint32_t step;
+      uint8_t data_length;
+      uint8_t st_data;
+      uint8_t * data;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->header.serialize(outbuffer + offset);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_height;
-      u_height.real = this->height;
-      *(outbuffer + offset + 0) = (u_height.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_height.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_height.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_height.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF;
       offset += sizeof(this->height);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_width;
-      u_width.real = this->width;
-      *(outbuffer + offset + 0) = (u_width.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_width.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_width.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_width.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF;
       offset += sizeof(this->width);
-      long * length_encoding = (long *)(outbuffer + offset);
+      uint32_t * length_encoding = (uint32_t *)(outbuffer + offset);
       *length_encoding = strlen( (const char*) this->encoding);
       offset += 4;
       memcpy(outbuffer + offset, this->encoding, *length_encoding);
       offset += *length_encoding;
-      union {
-        unsigned char real;
-        unsigned char base;
-      } u_is_bigendian;
-      u_is_bigendian.real = this->is_bigendian;
-      *(outbuffer + offset + 0) = (u_is_bigendian.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->is_bigendian >> (8 * 0)) & 0xFF;
       offset += sizeof(this->is_bigendian);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_step;
-      u_step.real = this->step;
-      *(outbuffer + offset + 0) = (u_step.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_step.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_step.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_step.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->step >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->step >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->step >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->step >> (8 * 3)) & 0xFF;
       offset += sizeof(this->step);
       *(outbuffer + offset++) = data_length;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < data_length; i++){
-      union {
-        unsigned char real;
-        unsigned char base;
-      } u_datai;
-      u_datai.real = this->data[i];
-      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+      for( uint8_t i = 0; i < data_length; i++){
+      *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF;
       offset += sizeof(this->data[i]);
       }
       return offset;
@@ -89,75 +64,46 @@
     {
       int offset = 0;
       offset += this->header.deserialize(inbuffer + offset);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_height;
-      u_height.base = 0;
-      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->height = u_height.real;
+      this->height |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       offset += sizeof(this->height);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_width;
-      u_width.base = 0;
-      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->width = u_width.real;
+      this->width |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       offset += sizeof(this->width);
       uint32_t length_encoding = *(uint32_t *)(inbuffer + offset);
       offset += 4;
       for(unsigned int k= offset; k< offset+length_encoding; ++k){
           inbuffer[k-1]=inbuffer[k];
-           }
+      }
       inbuffer[offset+length_encoding-1]=0;
       this->encoding = (char *)(inbuffer + offset-1);
       offset += length_encoding;
-      union {
-        unsigned char real;
-        unsigned char base;
-      } u_is_bigendian;
-      u_is_bigendian.base = 0;
-      u_is_bigendian.base |= ((typeof(u_is_bigendian.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      this->is_bigendian = u_is_bigendian.real;
+      this->is_bigendian |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
       offset += sizeof(this->is_bigendian);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_step;
-      u_step.base = 0;
-      u_step.base |= ((typeof(u_step.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_step.base |= ((typeof(u_step.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_step.base |= ((typeof(u_step.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_step.base |= ((typeof(u_step.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->step = u_step.real;
+      this->step |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       offset += sizeof(this->step);
-      unsigned char data_lengthT = *(inbuffer + offset++);
+      uint8_t data_lengthT = *(inbuffer + offset++);
       if(data_lengthT > data_length)
-        this->data = (unsigned char*)realloc(this->data, data_lengthT * sizeof(unsigned char));
+        this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t));
       offset += 3;
       data_length = data_lengthT;
-      for( unsigned char i = 0; i < data_length; i++){
-      union {
-        unsigned char real;
-        unsigned char base;
-      } u_st_data;
-      u_st_data.base = 0;
-      u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      this->st_data = u_st_data.real;
+      for( uint8_t i = 0; i < data_length; i++){
+      this->st_data |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
       offset += sizeof(this->st_data);
-        memcpy( &(this->data[i]), &(this->st_data), sizeof(unsigned char));
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t));
       }
      return offset;
     }
 
-   virtual const char * getType(){ return "sensor_msgs/Image"; };
+    virtual const char * getType(){ return "sensor_msgs/Image"; };
+    virtual const char * getMD5(){ return "060021388200f6f0f447d0fcd9c64743"; };
 
   };
 
--- a/sensor_msgs/Imu.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/sensor_msgs/Imu.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_Imu_h
-#define ros_Imu_h
+#ifndef _ROS_sensor_msgs_Imu_h
+#define _ROS_sensor_msgs_Imu_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "std_msgs/Header.h"
 #include "geometry_msgs/Quaternion.h"
 #include "geometry_msgs/Vector3.h"
@@ -23,18 +23,18 @@
       geometry_msgs::Vector3 linear_acceleration;
       float linear_acceleration_covariance[9];
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->header.serialize(outbuffer + offset);
       offset += this->orientation.serialize(outbuffer + offset);
       unsigned char * orientation_covariance_val = (unsigned char *) this->orientation_covariance;
-      for( unsigned char i = 0; i < 9; i++){
-      long * val_orientation_covariancei = (long *) &(this->orientation_covariance[i]);
-      long exp_orientation_covariancei = (((*val_orientation_covariancei)>>23)&255);
+      for( uint8_t i = 0; i < 9; i++){
+      int32_t * val_orientation_covariancei = (long *) &(this->orientation_covariance[i]);
+      int32_t exp_orientation_covariancei = (((*val_orientation_covariancei)>>23)&255);
       if(exp_orientation_covariancei != 0)
         exp_orientation_covariancei += 1023-127;
-      long sig_orientation_covariancei = *val_orientation_covariancei;
+      int32_t sig_orientation_covariancei = *val_orientation_covariancei;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
@@ -47,12 +47,12 @@
       }
       offset += this->angular_velocity.serialize(outbuffer + offset);
       unsigned char * angular_velocity_covariance_val = (unsigned char *) this->angular_velocity_covariance;
-      for( unsigned char i = 0; i < 9; i++){
-      long * val_angular_velocity_covariancei = (long *) &(this->angular_velocity_covariance[i]);
-      long exp_angular_velocity_covariancei = (((*val_angular_velocity_covariancei)>>23)&255);
+      for( uint8_t i = 0; i < 9; i++){
+      int32_t * val_angular_velocity_covariancei = (long *) &(this->angular_velocity_covariance[i]);
+      int32_t exp_angular_velocity_covariancei = (((*val_angular_velocity_covariancei)>>23)&255);
       if(exp_angular_velocity_covariancei != 0)
         exp_angular_velocity_covariancei += 1023-127;
-      long sig_angular_velocity_covariancei = *val_angular_velocity_covariancei;
+      int32_t sig_angular_velocity_covariancei = *val_angular_velocity_covariancei;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
@@ -65,12 +65,12 @@
       }
       offset += this->linear_acceleration.serialize(outbuffer + offset);
       unsigned char * linear_acceleration_covariance_val = (unsigned char *) this->linear_acceleration_covariance;
-      for( unsigned char i = 0; i < 9; i++){
-      long * val_linear_acceleration_covariancei = (long *) &(this->linear_acceleration_covariance[i]);
-      long exp_linear_acceleration_covariancei = (((*val_linear_acceleration_covariancei)>>23)&255);
+      for( uint8_t i = 0; i < 9; i++){
+      int32_t * val_linear_acceleration_covariancei = (long *) &(this->linear_acceleration_covariance[i]);
+      int32_t exp_linear_acceleration_covariancei = (((*val_linear_acceleration_covariancei)>>23)&255);
       if(exp_linear_acceleration_covariancei != 0)
         exp_linear_acceleration_covariancei += 1023-127;
-      long sig_linear_acceleration_covariancei = *val_linear_acceleration_covariancei;
+      int32_t sig_linear_acceleration_covariancei = *val_linear_acceleration_covariancei;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
@@ -89,46 +89,46 @@
       int offset = 0;
       offset += this->header.deserialize(inbuffer + offset);
       offset += this->orientation.deserialize(inbuffer + offset);
-      unsigned char * orientation_covariance_val = (unsigned char *) this->orientation_covariance;
-      for( unsigned char i = 0; i < 9; i++){
-      unsigned long * val_orientation_covariancei = (unsigned long*) &(this->orientation_covariance[i]);
+      uint8_t * orientation_covariance_val = (uint8_t*) this->orientation_covariance;
+      for( uint8_t i = 0; i < 9; i++){
+      uint32_t * val_orientation_covariancei = (uint32_t*) &(this->orientation_covariance[i]);
       offset += 3;
-      *val_orientation_covariancei = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-      *val_orientation_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-      *val_orientation_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-      *val_orientation_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-      unsigned long exp_orientation_covariancei = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-      exp_orientation_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      *val_orientation_covariancei = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_orientation_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_orientation_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_orientation_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_orientation_covariancei = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_orientation_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
       if(exp_orientation_covariancei !=0)
         *val_orientation_covariancei |= ((exp_orientation_covariancei)-1023+127)<<23;
       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->orientation_covariance[i] = -this->orientation_covariance[i];
       }
       offset += this->angular_velocity.deserialize(inbuffer + offset);
-      unsigned char * angular_velocity_covariance_val = (unsigned char *) this->angular_velocity_covariance;
-      for( unsigned char i = 0; i < 9; i++){
-      unsigned long * val_angular_velocity_covariancei = (unsigned long*) &(this->angular_velocity_covariance[i]);
+      uint8_t * angular_velocity_covariance_val = (uint8_t*) this->angular_velocity_covariance;
+      for( uint8_t i = 0; i < 9; i++){
+      uint32_t * val_angular_velocity_covariancei = (uint32_t*) &(this->angular_velocity_covariance[i]);
       offset += 3;
-      *val_angular_velocity_covariancei = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-      *val_angular_velocity_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-      *val_angular_velocity_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-      *val_angular_velocity_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-      unsigned long exp_angular_velocity_covariancei = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-      exp_angular_velocity_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      *val_angular_velocity_covariancei = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_angular_velocity_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_angular_velocity_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_angular_velocity_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_angular_velocity_covariancei = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_angular_velocity_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
       if(exp_angular_velocity_covariancei !=0)
         *val_angular_velocity_covariancei |= ((exp_angular_velocity_covariancei)-1023+127)<<23;
       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->angular_velocity_covariance[i] = -this->angular_velocity_covariance[i];
       }
       offset += this->linear_acceleration.deserialize(inbuffer + offset);
-      unsigned char * linear_acceleration_covariance_val = (unsigned char *) this->linear_acceleration_covariance;
-      for( unsigned char i = 0; i < 9; i++){
-      unsigned long * val_linear_acceleration_covariancei = (unsigned long*) &(this->linear_acceleration_covariance[i]);
+      uint8_t * linear_acceleration_covariance_val = (uint8_t*) this->linear_acceleration_covariance;
+      for( uint8_t i = 0; i < 9; i++){
+      uint32_t * val_linear_acceleration_covariancei = (uint32_t*) &(this->linear_acceleration_covariance[i]);
       offset += 3;
-      *val_linear_acceleration_covariancei = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-      *val_linear_acceleration_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-      *val_linear_acceleration_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-      *val_linear_acceleration_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-      unsigned long exp_linear_acceleration_covariancei = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-      exp_linear_acceleration_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      *val_linear_acceleration_covariancei = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_linear_acceleration_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_linear_acceleration_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_linear_acceleration_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_linear_acceleration_covariancei = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_linear_acceleration_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
       if(exp_linear_acceleration_covariancei !=0)
         *val_linear_acceleration_covariancei |= ((exp_linear_acceleration_covariancei)-1023+127)<<23;
       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->linear_acceleration_covariance[i] = -this->linear_acceleration_covariance[i];
@@ -136,7 +136,8 @@
      return offset;
     }
 
-   virtual const char * getType(){ return "sensor_msgs/Imu"; };
+    virtual const char * getType(){ return "sensor_msgs/Imu"; };
+    virtual const char * getMD5(){ return "6a62c6daae103f4ff57a132d6f95cec2"; };
 
   };
 
--- a/sensor_msgs/JointState.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/sensor_msgs/JointState.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_JointState_h
-#define ros_JointState_h
+#ifndef _ROS_sensor_msgs_JointState_h
+#define _ROS_sensor_msgs_JointState_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "std_msgs/Header.h"
 
 namespace sensor_msgs
@@ -14,20 +14,20 @@
   {
     public:
       std_msgs::Header header;
-      unsigned char name_length;
+      uint8_t name_length;
       char* st_name;
       char* * name;
-      unsigned char position_length;
+      uint8_t position_length;
       float st_position;
       float * position;
-      unsigned char velocity_length;
+      uint8_t velocity_length;
       float st_velocity;
       float * velocity;
-      unsigned char effort_length;
+      uint8_t effort_length;
       float st_effort;
       float * effort;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->header.serialize(outbuffer + offset);
@@ -35,8 +35,8 @@
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < name_length; i++){
-      long * length_namei = (long *)(outbuffer + offset);
+      for( uint8_t i = 0; i < name_length; i++){
+      uint32_t * length_namei = (uint32_t *)(outbuffer + offset);
       *length_namei = strlen( (const char*) this->name[i]);
       offset += 4;
       memcpy(outbuffer + offset, this->name[i], *length_namei);
@@ -46,12 +46,12 @@
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < position_length; i++){
-      long * val_positioni = (long *) &(this->position[i]);
-      long exp_positioni = (((*val_positioni)>>23)&255);
+      for( uint8_t i = 0; i < position_length; i++){
+      int32_t * val_positioni = (long *) &(this->position[i]);
+      int32_t exp_positioni = (((*val_positioni)>>23)&255);
       if(exp_positioni != 0)
         exp_positioni += 1023-127;
-      long sig_positioni = *val_positioni;
+      int32_t sig_positioni = *val_positioni;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
@@ -66,12 +66,12 @@
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < velocity_length; i++){
-      long * val_velocityi = (long *) &(this->velocity[i]);
-      long exp_velocityi = (((*val_velocityi)>>23)&255);
+      for( uint8_t i = 0; i < velocity_length; i++){
+      int32_t * val_velocityi = (long *) &(this->velocity[i]);
+      int32_t exp_velocityi = (((*val_velocityi)>>23)&255);
       if(exp_velocityi != 0)
         exp_velocityi += 1023-127;
-      long sig_velocityi = *val_velocityi;
+      int32_t sig_velocityi = *val_velocityi;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
@@ -86,12 +86,12 @@
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < effort_length; i++){
-      long * val_efforti = (long *) &(this->effort[i]);
-      long exp_efforti = (((*val_efforti)>>23)&255);
+      for( uint8_t i = 0; i < effort_length; i++){
+      int32_t * val_efforti = (long *) &(this->effort[i]);
+      int32_t exp_efforti = (((*val_efforti)>>23)&255);
       if(exp_efforti != 0)
         exp_efforti += 1023-127;
-      long sig_efforti = *val_efforti;
+      int32_t sig_efforti = *val_efforti;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
@@ -109,74 +109,74 @@
     {
       int offset = 0;
       offset += this->header.deserialize(inbuffer + offset);
-      unsigned char name_lengthT = *(inbuffer + offset++);
+      uint8_t name_lengthT = *(inbuffer + offset++);
       if(name_lengthT > name_length)
         this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*));
       offset += 3;
       name_length = name_lengthT;
-      for( unsigned char i = 0; i < name_length; i++){
+      for( uint8_t i = 0; i < name_length; i++){
       uint32_t length_st_name = *(uint32_t *)(inbuffer + offset);
       offset += 4;
       for(unsigned int k= offset; k< offset+length_st_name; ++k){
           inbuffer[k-1]=inbuffer[k];
-           }
+      }
       inbuffer[offset+length_st_name-1]=0;
       this->st_name = (char *)(inbuffer + offset-1);
       offset += length_st_name;
         memcpy( &(this->name[i]), &(this->st_name), sizeof(char*));
       }
-      unsigned char position_lengthT = *(inbuffer + offset++);
+      uint8_t position_lengthT = *(inbuffer + offset++);
       if(position_lengthT > position_length)
         this->position = (float*)realloc(this->position, position_lengthT * sizeof(float));
       offset += 3;
       position_length = position_lengthT;
-      for( unsigned char i = 0; i < position_length; i++){
-      unsigned long * val_st_position = (unsigned long*) &(this->st_position);
+      for( uint8_t i = 0; i < position_length; i++){
+      uint32_t * val_st_position = (uint32_t*) &(this->st_position);
       offset += 3;
-      *val_st_position = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-      *val_st_position |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-      *val_st_position |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-      *val_st_position |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-      unsigned long exp_st_position = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-      exp_st_position |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      *val_st_position = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_st_position |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_st_position |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_st_position |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_st_position = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_st_position |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
       if(exp_st_position !=0)
         *val_st_position |= ((exp_st_position)-1023+127)<<23;
       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->st_position = -this->st_position;
         memcpy( &(this->position[i]), &(this->st_position), sizeof(float));
       }
-      unsigned char velocity_lengthT = *(inbuffer + offset++);
+      uint8_t velocity_lengthT = *(inbuffer + offset++);
       if(velocity_lengthT > velocity_length)
         this->velocity = (float*)realloc(this->velocity, velocity_lengthT * sizeof(float));
       offset += 3;
       velocity_length = velocity_lengthT;
-      for( unsigned char i = 0; i < velocity_length; i++){
-      unsigned long * val_st_velocity = (unsigned long*) &(this->st_velocity);
+      for( uint8_t i = 0; i < velocity_length; i++){
+      uint32_t * val_st_velocity = (uint32_t*) &(this->st_velocity);
       offset += 3;
-      *val_st_velocity = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-      *val_st_velocity |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-      *val_st_velocity |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-      *val_st_velocity |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-      unsigned long exp_st_velocity = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-      exp_st_velocity |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      *val_st_velocity = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_st_velocity |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_st_velocity |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_st_velocity |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_st_velocity = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_st_velocity |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
       if(exp_st_velocity !=0)
         *val_st_velocity |= ((exp_st_velocity)-1023+127)<<23;
       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->st_velocity = -this->st_velocity;
         memcpy( &(this->velocity[i]), &(this->st_velocity), sizeof(float));
       }
-      unsigned char effort_lengthT = *(inbuffer + offset++);
+      uint8_t effort_lengthT = *(inbuffer + offset++);
       if(effort_lengthT > effort_length)
         this->effort = (float*)realloc(this->effort, effort_lengthT * sizeof(float));
       offset += 3;
       effort_length = effort_lengthT;
-      for( unsigned char i = 0; i < effort_length; i++){
-      unsigned long * val_st_effort = (unsigned long*) &(this->st_effort);
+      for( uint8_t i = 0; i < effort_length; i++){
+      uint32_t * val_st_effort = (uint32_t*) &(this->st_effort);
       offset += 3;
-      *val_st_effort = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-      *val_st_effort |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-      *val_st_effort |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-      *val_st_effort |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-      unsigned long exp_st_effort = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-      exp_st_effort |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      *val_st_effort = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_st_effort |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_st_effort |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_st_effort |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_st_effort = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_st_effort |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
       if(exp_st_effort !=0)
         *val_st_effort |= ((exp_st_effort)-1023+127)<<23;
       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->st_effort = -this->st_effort;
@@ -185,7 +185,8 @@
      return offset;
     }
 
-   virtual const char * getType(){ return "sensor_msgs/JointState"; };
+    virtual const char * getType(){ return "sensor_msgs/JointState"; };
+    virtual const char * getMD5(){ return "3066dcd76a6cfaef579bd0f34173e9fd"; };
 
   };
 
--- a/sensor_msgs/LaserScan.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/sensor_msgs/LaserScan.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_LaserScan_h
-#define ros_LaserScan_h
+#ifndef _ROS_sensor_msgs_LaserScan_h
+#define _ROS_sensor_msgs_LaserScan_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "std_msgs/Header.h"
 
 namespace sensor_msgs
@@ -21,20 +21,20 @@
       float scan_time;
       float range_min;
       float range_max;
-      unsigned char ranges_length;
+      uint8_t ranges_length;
       float st_ranges;
       float * ranges;
-      unsigned char intensities_length;
+      uint8_t intensities_length;
       float st_intensities;
       float * intensities;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->header.serialize(outbuffer + offset);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_angle_min;
       u_angle_min.real = this->angle_min;
       *(outbuffer + offset + 0) = (u_angle_min.base >> (8 * 0)) & 0xFF;
@@ -44,7 +44,7 @@
       offset += sizeof(this->angle_min);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_angle_max;
       u_angle_max.real = this->angle_max;
       *(outbuffer + offset + 0) = (u_angle_max.base >> (8 * 0)) & 0xFF;
@@ -54,7 +54,7 @@
       offset += sizeof(this->angle_max);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_angle_increment;
       u_angle_increment.real = this->angle_increment;
       *(outbuffer + offset + 0) = (u_angle_increment.base >> (8 * 0)) & 0xFF;
@@ -64,7 +64,7 @@
       offset += sizeof(this->angle_increment);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_time_increment;
       u_time_increment.real = this->time_increment;
       *(outbuffer + offset + 0) = (u_time_increment.base >> (8 * 0)) & 0xFF;
@@ -74,7 +74,7 @@
       offset += sizeof(this->time_increment);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_scan_time;
       u_scan_time.real = this->scan_time;
       *(outbuffer + offset + 0) = (u_scan_time.base >> (8 * 0)) & 0xFF;
@@ -84,7 +84,7 @@
       offset += sizeof(this->scan_time);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_range_min;
       u_range_min.real = this->range_min;
       *(outbuffer + offset + 0) = (u_range_min.base >> (8 * 0)) & 0xFF;
@@ -94,7 +94,7 @@
       offset += sizeof(this->range_min);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_range_max;
       u_range_max.real = this->range_max;
       *(outbuffer + offset + 0) = (u_range_max.base >> (8 * 0)) & 0xFF;
@@ -106,10 +106,10 @@
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < ranges_length; i++){
+      for( uint8_t i = 0; i < ranges_length; i++){
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_rangesi;
       u_rangesi.real = this->ranges[i];
       *(outbuffer + offset + 0) = (u_rangesi.base >> (8 * 0)) & 0xFF;
@@ -122,10 +122,10 @@
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < intensities_length; i++){
+      for( uint8_t i = 0; i < intensities_length; i++){
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_intensitiesi;
       u_intensitiesi.real = this->intensities[i];
       *(outbuffer + offset + 0) = (u_intensitiesi.base >> (8 * 0)) & 0xFF;
@@ -143,115 +143,115 @@
       offset += this->header.deserialize(inbuffer + offset);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_angle_min;
       u_angle_min.base = 0;
-      u_angle_min.base |= ((typeof(u_angle_min.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_angle_min.base |= ((typeof(u_angle_min.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_angle_min.base |= ((typeof(u_angle_min.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_angle_min.base |= ((typeof(u_angle_min.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_angle_min.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       this->angle_min = u_angle_min.real;
       offset += sizeof(this->angle_min);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_angle_max;
       u_angle_max.base = 0;
-      u_angle_max.base |= ((typeof(u_angle_max.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_angle_max.base |= ((typeof(u_angle_max.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_angle_max.base |= ((typeof(u_angle_max.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_angle_max.base |= ((typeof(u_angle_max.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_angle_max.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       this->angle_max = u_angle_max.real;
       offset += sizeof(this->angle_max);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_angle_increment;
       u_angle_increment.base = 0;
-      u_angle_increment.base |= ((typeof(u_angle_increment.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_angle_increment.base |= ((typeof(u_angle_increment.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_angle_increment.base |= ((typeof(u_angle_increment.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_angle_increment.base |= ((typeof(u_angle_increment.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_angle_increment.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       this->angle_increment = u_angle_increment.real;
       offset += sizeof(this->angle_increment);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_time_increment;
       u_time_increment.base = 0;
-      u_time_increment.base |= ((typeof(u_time_increment.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_time_increment.base |= ((typeof(u_time_increment.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_time_increment.base |= ((typeof(u_time_increment.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_time_increment.base |= ((typeof(u_time_increment.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_time_increment.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       this->time_increment = u_time_increment.real;
       offset += sizeof(this->time_increment);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_scan_time;
       u_scan_time.base = 0;
-      u_scan_time.base |= ((typeof(u_scan_time.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_scan_time.base |= ((typeof(u_scan_time.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_scan_time.base |= ((typeof(u_scan_time.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_scan_time.base |= ((typeof(u_scan_time.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_scan_time.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       this->scan_time = u_scan_time.real;
       offset += sizeof(this->scan_time);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_range_min;
       u_range_min.base = 0;
-      u_range_min.base |= ((typeof(u_range_min.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_range_min.base |= ((typeof(u_range_min.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_range_min.base |= ((typeof(u_range_min.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_range_min.base |= ((typeof(u_range_min.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_range_min.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       this->range_min = u_range_min.real;
       offset += sizeof(this->range_min);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_range_max;
       u_range_max.base = 0;
-      u_range_max.base |= ((typeof(u_range_max.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_range_max.base |= ((typeof(u_range_max.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_range_max.base |= ((typeof(u_range_max.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_range_max.base |= ((typeof(u_range_max.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_range_max.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       this->range_max = u_range_max.real;
       offset += sizeof(this->range_max);
-      unsigned char ranges_lengthT = *(inbuffer + offset++);
+      uint8_t ranges_lengthT = *(inbuffer + offset++);
       if(ranges_lengthT > ranges_length)
         this->ranges = (float*)realloc(this->ranges, ranges_lengthT * sizeof(float));
       offset += 3;
       ranges_length = ranges_lengthT;
-      for( unsigned char i = 0; i < ranges_length; i++){
+      for( uint8_t i = 0; i < ranges_length; i++){
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_st_ranges;
       u_st_ranges.base = 0;
-      u_st_ranges.base |= ((typeof(u_st_ranges.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_st_ranges.base |= ((typeof(u_st_ranges.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_st_ranges.base |= ((typeof(u_st_ranges.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_st_ranges.base |= ((typeof(u_st_ranges.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_ranges.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       this->st_ranges = u_st_ranges.real;
       offset += sizeof(this->st_ranges);
         memcpy( &(this->ranges[i]), &(this->st_ranges), sizeof(float));
       }
-      unsigned char intensities_lengthT = *(inbuffer + offset++);
+      uint8_t intensities_lengthT = *(inbuffer + offset++);
       if(intensities_lengthT > intensities_length)
         this->intensities = (float*)realloc(this->intensities, intensities_lengthT * sizeof(float));
       offset += 3;
       intensities_length = intensities_lengthT;
-      for( unsigned char i = 0; i < intensities_length; i++){
+      for( uint8_t i = 0; i < intensities_length; i++){
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_st_intensities;
       u_st_intensities.base = 0;
-      u_st_intensities.base |= ((typeof(u_st_intensities.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_st_intensities.base |= ((typeof(u_st_intensities.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_st_intensities.base |= ((typeof(u_st_intensities.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_st_intensities.base |= ((typeof(u_st_intensities.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_intensities.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       this->st_intensities = u_st_intensities.real;
       offset += sizeof(this->st_intensities);
         memcpy( &(this->intensities[i]), &(this->st_intensities), sizeof(float));
@@ -259,7 +259,8 @@
      return offset;
     }
 
-   virtual const char * getType(){ return "sensor_msgs/LaserScan"; };
+    virtual const char * getType(){ return "sensor_msgs/LaserScan"; };
+    virtual const char * getMD5(){ return "90c7ef2dc6895d81024acba2ac42f369"; };
 
   };
 
--- a/sensor_msgs/NavSatFix.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/sensor_msgs/NavSatFix.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_NavSatFix_h
-#define ros_NavSatFix_h
+#ifndef _ROS_sensor_msgs_NavSatFix_h
+#define _ROS_sensor_msgs_NavSatFix_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "std_msgs/Header.h"
 #include "sensor_msgs/NavSatStatus.h"
 
@@ -20,22 +20,22 @@
       float longitude;
       float altitude;
       float position_covariance[9];
-      unsigned char position_covariance_type;
-      enum { COVARIANCE_TYPE_UNKNOWN = 0 };
-      enum { COVARIANCE_TYPE_APPROXIMATED = 1 };
-      enum { COVARIANCE_TYPE_DIAGONAL_KNOWN = 2 };
-      enum { COVARIANCE_TYPE_KNOWN = 3 };
+      uint8_t position_covariance_type;
+      enum { COVARIANCE_TYPE_UNKNOWN =  0 };
+      enum { COVARIANCE_TYPE_APPROXIMATED =  1 };
+      enum { COVARIANCE_TYPE_DIAGONAL_KNOWN =  2 };
+      enum { COVARIANCE_TYPE_KNOWN =  3 };
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->header.serialize(outbuffer + offset);
       offset += this->status.serialize(outbuffer + offset);
-      long * val_latitude = (long *) &(this->latitude);
-      long exp_latitude = (((*val_latitude)>>23)&255);
+      int32_t * val_latitude = (long *) &(this->latitude);
+      int32_t exp_latitude = (((*val_latitude)>>23)&255);
       if(exp_latitude != 0)
         exp_latitude += 1023-127;
-      long sig_latitude = *val_latitude;
+      int32_t sig_latitude = *val_latitude;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
@@ -45,11 +45,11 @@
       *(outbuffer + offset++) = ((exp_latitude<<4) & 0xF0) | ((sig_latitude>>19)&0x0F);
       *(outbuffer + offset++) = (exp_latitude>>4) & 0x7F;
       if(this->latitude < 0) *(outbuffer + offset -1) |= 0x80;
-      long * val_longitude = (long *) &(this->longitude);
-      long exp_longitude = (((*val_longitude)>>23)&255);
+      int32_t * val_longitude = (long *) &(this->longitude);
+      int32_t exp_longitude = (((*val_longitude)>>23)&255);
       if(exp_longitude != 0)
         exp_longitude += 1023-127;
-      long sig_longitude = *val_longitude;
+      int32_t sig_longitude = *val_longitude;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
@@ -59,11 +59,11 @@
       *(outbuffer + offset++) = ((exp_longitude<<4) & 0xF0) | ((sig_longitude>>19)&0x0F);
       *(outbuffer + offset++) = (exp_longitude>>4) & 0x7F;
       if(this->longitude < 0) *(outbuffer + offset -1) |= 0x80;
-      long * val_altitude = (long *) &(this->altitude);
-      long exp_altitude = (((*val_altitude)>>23)&255);
+      int32_t * val_altitude = (long *) &(this->altitude);
+      int32_t exp_altitude = (((*val_altitude)>>23)&255);
       if(exp_altitude != 0)
         exp_altitude += 1023-127;
-      long sig_altitude = *val_altitude;
+      int32_t sig_altitude = *val_altitude;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
@@ -74,12 +74,12 @@
       *(outbuffer + offset++) = (exp_altitude>>4) & 0x7F;
       if(this->altitude < 0) *(outbuffer + offset -1) |= 0x80;
       unsigned char * position_covariance_val = (unsigned char *) this->position_covariance;
-      for( unsigned char i = 0; i < 9; i++){
-      long * val_position_covariancei = (long *) &(this->position_covariance[i]);
-      long exp_position_covariancei = (((*val_position_covariancei)>>23)&255);
+      for( uint8_t i = 0; i < 9; i++){
+      int32_t * val_position_covariancei = (long *) &(this->position_covariance[i]);
+      int32_t exp_position_covariancei = (((*val_position_covariancei)>>23)&255);
       if(exp_position_covariancei != 0)
         exp_position_covariancei += 1023-127;
-      long sig_position_covariancei = *val_position_covariancei;
+      int32_t sig_position_covariancei = *val_position_covariancei;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
@@ -90,12 +90,7 @@
       *(outbuffer + offset++) = (exp_position_covariancei>>4) & 0x7F;
       if(this->position_covariance[i] < 0) *(outbuffer + offset -1) |= 0x80;
       }
-      union {
-        unsigned char real;
-        unsigned char base;
-      } u_position_covariance_type;
-      u_position_covariance_type.real = this->position_covariance_type;
-      *(outbuffer + offset + 0) = (u_position_covariance_type.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->position_covariance_type >> (8 * 0)) & 0xFF;
       offset += sizeof(this->position_covariance_type);
       return offset;
     }
@@ -105,65 +100,60 @@
       int offset = 0;
       offset += this->header.deserialize(inbuffer + offset);
       offset += this->status.deserialize(inbuffer + offset);
-      unsigned long * val_latitude = (unsigned long*) &(this->latitude);
+      uint32_t * val_latitude = (uint32_t*) &(this->latitude);
       offset += 3;
-      *val_latitude = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-      *val_latitude |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-      *val_latitude |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-      *val_latitude |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-      unsigned long exp_latitude = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-      exp_latitude |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      *val_latitude = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_latitude |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_latitude |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_latitude |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_latitude = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_latitude |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
       if(exp_latitude !=0)
         *val_latitude |= ((exp_latitude)-1023+127)<<23;
       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->latitude = -this->latitude;
-      unsigned long * val_longitude = (unsigned long*) &(this->longitude);
+      uint32_t * val_longitude = (uint32_t*) &(this->longitude);
       offset += 3;
-      *val_longitude = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-      *val_longitude |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-      *val_longitude |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-      *val_longitude |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-      unsigned long exp_longitude = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-      exp_longitude |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      *val_longitude = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_longitude |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_longitude |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_longitude |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_longitude = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_longitude |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
       if(exp_longitude !=0)
         *val_longitude |= ((exp_longitude)-1023+127)<<23;
       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->longitude = -this->longitude;
-      unsigned long * val_altitude = (unsigned long*) &(this->altitude);
+      uint32_t * val_altitude = (uint32_t*) &(this->altitude);
       offset += 3;
-      *val_altitude = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-      *val_altitude |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-      *val_altitude |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-      *val_altitude |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-      unsigned long exp_altitude = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-      exp_altitude |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      *val_altitude = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_altitude |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_altitude |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_altitude |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_altitude = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_altitude |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
       if(exp_altitude !=0)
         *val_altitude |= ((exp_altitude)-1023+127)<<23;
       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->altitude = -this->altitude;
-      unsigned char * position_covariance_val = (unsigned char *) this->position_covariance;
-      for( unsigned char i = 0; i < 9; i++){
-      unsigned long * val_position_covariancei = (unsigned long*) &(this->position_covariance[i]);
+      uint8_t * position_covariance_val = (uint8_t*) this->position_covariance;
+      for( uint8_t i = 0; i < 9; i++){
+      uint32_t * val_position_covariancei = (uint32_t*) &(this->position_covariance[i]);
       offset += 3;
-      *val_position_covariancei = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-      *val_position_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-      *val_position_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-      *val_position_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-      unsigned long exp_position_covariancei = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-      exp_position_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      *val_position_covariancei = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_position_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_position_covariancei |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_position_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
+      uint32_t exp_position_covariancei = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_position_covariancei |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
       if(exp_position_covariancei !=0)
         *val_position_covariancei |= ((exp_position_covariancei)-1023+127)<<23;
       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->position_covariance[i] = -this->position_covariance[i];
       }
-      union {
-        unsigned char real;
-        unsigned char base;
-      } u_position_covariance_type;
-      u_position_covariance_type.base = 0;
-      u_position_covariance_type.base |= ((typeof(u_position_covariance_type.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      this->position_covariance_type = u_position_covariance_type.real;
+      this->position_covariance_type |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
       offset += sizeof(this->position_covariance_type);
      return offset;
     }
 
-   virtual const char * getType(){ return "sensor_msgs/NavSatFix"; };
+    virtual const char * getType(){ return "sensor_msgs/NavSatFix"; };
+    virtual const char * getMD5(){ return "2d3a8cd499b9b4a0249fb98fd05cfa48"; };
 
   };
 
--- a/sensor_msgs/NavSatStatus.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/sensor_msgs/NavSatStatus.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_NavSatStatus_h
-#define ros_NavSatStatus_h
+#ifndef _ROS_sensor_msgs_NavSatStatus_h
+#define _ROS_sensor_msgs_NavSatStatus_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 
 namespace sensor_msgs
 {
@@ -12,34 +12,29 @@
   class NavSatStatus : public ros::Msg
   {
     public:
-      signed char status;
-      unsigned short service;
-      enum { STATUS_NO_FIX = -1 };
-      enum { STATUS_FIX = 0 };
-      enum { STATUS_SBAS_FIX = 1 };
-      enum { STATUS_GBAS_FIX = 2 };
-      enum { SERVICE_GPS = 1 };
-      enum { SERVICE_GLONASS = 2 };
-      enum { SERVICE_COMPASS = 4 };
-      enum { SERVICE_GALILEO = 8 };
+      int8_t status;
+      uint16_t service;
+      enum { STATUS_NO_FIX =   -1         };
+      enum { STATUS_FIX =       0         };
+      enum { STATUS_SBAS_FIX =  1         };
+      enum { STATUS_GBAS_FIX =  2         };
+      enum { SERVICE_GPS =      1 };
+      enum { SERVICE_GLONASS =  2 };
+      enum { SERVICE_COMPASS =  4       };
+      enum { SERVICE_GALILEO =  8 };
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       union {
-        signed char real;
-        unsigned char base;
+        int8_t real;
+        uint8_t base;
       } u_status;
       u_status.real = this->status;
       *(outbuffer + offset + 0) = (u_status.base >> (8 * 0)) & 0xFF;
       offset += sizeof(this->status);
-      union {
-        unsigned short real;
-        unsigned short base;
-      } u_service;
-      u_service.real = this->service;
-      *(outbuffer + offset + 0) = (u_service.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_service.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->service >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->service >> (8 * 1)) & 0xFF;
       offset += sizeof(this->service);
       return offset;
     }
@@ -48,26 +43,21 @@
     {
       int offset = 0;
       union {
-        signed char real;
-        unsigned char base;
+        int8_t real;
+        uint8_t base;
       } u_status;
       u_status.base = 0;
-      u_status.base |= ((typeof(u_status.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_status.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
       this->status = u_status.real;
       offset += sizeof(this->status);
-      union {
-        unsigned short real;
-        unsigned short base;
-      } u_service;
-      u_service.base = 0;
-      u_service.base |= ((typeof(u_service.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_service.base |= ((typeof(u_service.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      this->service = u_service.real;
+      this->service |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->service |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
       offset += sizeof(this->service);
      return offset;
     }
 
-   virtual const char * getType(){ return "sensor_msgs/NavSatStatus"; };
+    virtual const char * getType(){ return "sensor_msgs/NavSatStatus"; };
+    virtual const char * getMD5(){ return "331cdbddfa4bc96ffc3b9ad98900a54c"; };
 
   };
 
--- a/sensor_msgs/PointCloud.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/sensor_msgs/PointCloud.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_PointCloud_h
-#define ros_PointCloud_h
+#ifndef _ROS_sensor_msgs_PointCloud_h
+#define _ROS_sensor_msgs_PointCloud_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "std_msgs/Header.h"
 #include "geometry_msgs/Point32.h"
 #include "sensor_msgs/ChannelFloat32.h"
@@ -16,14 +16,14 @@
   {
     public:
       std_msgs::Header header;
-      unsigned char points_length;
+      uint8_t points_length;
       geometry_msgs::Point32 st_points;
       geometry_msgs::Point32 * points;
-      unsigned char channels_length;
+      uint8_t channels_length;
       sensor_msgs::ChannelFloat32 st_channels;
       sensor_msgs::ChannelFloat32 * channels;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->header.serialize(outbuffer + offset);
@@ -31,14 +31,14 @@
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < points_length; i++){
+      for( uint8_t i = 0; i < points_length; i++){
       offset += this->points[i].serialize(outbuffer + offset);
       }
       *(outbuffer + offset++) = channels_length;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < channels_length; i++){
+      for( uint8_t i = 0; i < channels_length; i++){
       offset += this->channels[i].serialize(outbuffer + offset);
       }
       return offset;
@@ -48,28 +48,29 @@
     {
       int offset = 0;
       offset += this->header.deserialize(inbuffer + offset);
-      unsigned char points_lengthT = *(inbuffer + offset++);
+      uint8_t points_lengthT = *(inbuffer + offset++);
       if(points_lengthT > points_length)
         this->points = (geometry_msgs::Point32*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point32));
       offset += 3;
       points_length = points_lengthT;
-      for( unsigned char i = 0; i < points_length; i++){
+      for( uint8_t i = 0; i < points_length; i++){
       offset += this->st_points.deserialize(inbuffer + offset);
         memcpy( &(this->points[i]), &(this->st_points), sizeof(geometry_msgs::Point32));
       }
-      unsigned char channels_lengthT = *(inbuffer + offset++);
+      uint8_t channels_lengthT = *(inbuffer + offset++);
       if(channels_lengthT > channels_length)
         this->channels = (sensor_msgs::ChannelFloat32*)realloc(this->channels, channels_lengthT * sizeof(sensor_msgs::ChannelFloat32));
       offset += 3;
       channels_length = channels_lengthT;
-      for( unsigned char i = 0; i < channels_length; i++){
+      for( uint8_t i = 0; i < channels_length; i++){
       offset += this->st_channels.deserialize(inbuffer + offset);
         memcpy( &(this->channels[i]), &(this->st_channels), sizeof(sensor_msgs::ChannelFloat32));
       }
      return offset;
     }
 
-   virtual const char * getType(){ return "sensor_msgs/PointCloud"; };
+    virtual const char * getType(){ return "sensor_msgs/PointCloud"; };
+    virtual const char * getMD5(){ return "d8e9c3f5afbdd8a130fd1d2763945fca"; };
 
   };
 
--- a/sensor_msgs/PointCloud2.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/sensor_msgs/PointCloud2.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_PointCloud2_h
-#define ros_PointCloud2_h
+#ifndef _ROS_sensor_msgs_PointCloud2_h
+#define _ROS_sensor_msgs_PointCloud2_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "std_msgs/Header.h"
 #include "sensor_msgs/PointField.h"
 
@@ -15,93 +15,68 @@
   {
     public:
       std_msgs::Header header;
-      unsigned long height;
-      unsigned long width;
-      unsigned char fields_length;
+      uint32_t height;
+      uint32_t width;
+      uint8_t fields_length;
       sensor_msgs::PointField st_fields;
       sensor_msgs::PointField * fields;
       bool is_bigendian;
-      unsigned long point_step;
-      unsigned long row_step;
-      unsigned char data_length;
-      unsigned char st_data;
-      unsigned char * data;
+      uint32_t point_step;
+      uint32_t row_step;
+      uint8_t data_length;
+      uint8_t st_data;
+      uint8_t * data;
       bool is_dense;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->header.serialize(outbuffer + offset);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_height;
-      u_height.real = this->height;
-      *(outbuffer + offset + 0) = (u_height.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_height.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_height.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_height.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF;
       offset += sizeof(this->height);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_width;
-      u_width.real = this->width;
-      *(outbuffer + offset + 0) = (u_width.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_width.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_width.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_width.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF;
       offset += sizeof(this->width);
       *(outbuffer + offset++) = fields_length;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < fields_length; i++){
+      for( uint8_t i = 0; i < fields_length; i++){
       offset += this->fields[i].serialize(outbuffer + offset);
       }
       union {
         bool real;
-        unsigned char base;
+        uint8_t base;
       } u_is_bigendian;
       u_is_bigendian.real = this->is_bigendian;
       *(outbuffer + offset + 0) = (u_is_bigendian.base >> (8 * 0)) & 0xFF;
       offset += sizeof(this->is_bigendian);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_point_step;
-      u_point_step.real = this->point_step;
-      *(outbuffer + offset + 0) = (u_point_step.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_point_step.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_point_step.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_point_step.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->point_step >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->point_step >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->point_step >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->point_step >> (8 * 3)) & 0xFF;
       offset += sizeof(this->point_step);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_row_step;
-      u_row_step.real = this->row_step;
-      *(outbuffer + offset + 0) = (u_row_step.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_row_step.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_row_step.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_row_step.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->row_step >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->row_step >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->row_step >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->row_step >> (8 * 3)) & 0xFF;
       offset += sizeof(this->row_step);
       *(outbuffer + offset++) = data_length;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < data_length; i++){
-      union {
-        unsigned char real;
-        unsigned char base;
-      } u_datai;
-      u_datai.real = this->data[i];
-      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+      for( uint8_t i = 0; i < data_length; i++){
+      *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF;
       offset += sizeof(this->data[i]);
       }
       union {
         bool real;
-        unsigned char base;
+        uint8_t base;
       } u_is_dense;
       u_is_dense.real = this->is_dense;
       *(outbuffer + offset + 0) = (u_is_dense.base >> (8 * 0)) & 0xFF;
@@ -113,95 +88,66 @@
     {
       int offset = 0;
       offset += this->header.deserialize(inbuffer + offset);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_height;
-      u_height.base = 0;
-      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->height = u_height.real;
+      this->height |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       offset += sizeof(this->height);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_width;
-      u_width.base = 0;
-      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->width = u_width.real;
+      this->width |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       offset += sizeof(this->width);
-      unsigned char fields_lengthT = *(inbuffer + offset++);
+      uint8_t fields_lengthT = *(inbuffer + offset++);
       if(fields_lengthT > fields_length)
         this->fields = (sensor_msgs::PointField*)realloc(this->fields, fields_lengthT * sizeof(sensor_msgs::PointField));
       offset += 3;
       fields_length = fields_lengthT;
-      for( unsigned char i = 0; i < fields_length; i++){
+      for( uint8_t i = 0; i < fields_length; i++){
       offset += this->st_fields.deserialize(inbuffer + offset);
         memcpy( &(this->fields[i]), &(this->st_fields), sizeof(sensor_msgs::PointField));
       }
       union {
         bool real;
-        unsigned char base;
+        uint8_t base;
       } u_is_bigendian;
       u_is_bigendian.base = 0;
-      u_is_bigendian.base |= ((typeof(u_is_bigendian.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_is_bigendian.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
       this->is_bigendian = u_is_bigendian.real;
       offset += sizeof(this->is_bigendian);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_point_step;
-      u_point_step.base = 0;
-      u_point_step.base |= ((typeof(u_point_step.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_point_step.base |= ((typeof(u_point_step.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_point_step.base |= ((typeof(u_point_step.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_point_step.base |= ((typeof(u_point_step.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->point_step = u_point_step.real;
+      this->point_step |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->point_step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->point_step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->point_step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       offset += sizeof(this->point_step);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_row_step;
-      u_row_step.base = 0;
-      u_row_step.base |= ((typeof(u_row_step.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_row_step.base |= ((typeof(u_row_step.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_row_step.base |= ((typeof(u_row_step.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_row_step.base |= ((typeof(u_row_step.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->row_step = u_row_step.real;
+      this->row_step |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->row_step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->row_step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->row_step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       offset += sizeof(this->row_step);
-      unsigned char data_lengthT = *(inbuffer + offset++);
+      uint8_t data_lengthT = *(inbuffer + offset++);
       if(data_lengthT > data_length)
-        this->data = (unsigned char*)realloc(this->data, data_lengthT * sizeof(unsigned char));
+        this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t));
       offset += 3;
       data_length = data_lengthT;
-      for( unsigned char i = 0; i < data_length; i++){
-      union {
-        unsigned char real;
-        unsigned char base;
-      } u_st_data;
-      u_st_data.base = 0;
-      u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      this->st_data = u_st_data.real;
+      for( uint8_t i = 0; i < data_length; i++){
+      this->st_data |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
       offset += sizeof(this->st_data);
-        memcpy( &(this->data[i]), &(this->st_data), sizeof(unsigned char));
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t));
       }
       union {
         bool real;
-        unsigned char base;
+        uint8_t base;
       } u_is_dense;
       u_is_dense.base = 0;
-      u_is_dense.base |= ((typeof(u_is_dense.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_is_dense.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
       this->is_dense = u_is_dense.real;
       offset += sizeof(this->is_dense);
      return offset;
     }
 
-   virtual const char * getType(){ return "sensor_msgs/PointCloud2"; };
+    virtual const char * getType(){ return "sensor_msgs/PointCloud2"; };
+    virtual const char * getMD5(){ return "1158d486dd51d683ce2f1be655c3c181"; };
 
   };
 
--- a/sensor_msgs/PointField.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/sensor_msgs/PointField.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_PointField_h
-#define ros_PointField_h
+#ifndef _ROS_sensor_msgs_PointField_h
+#define _ROS_sensor_msgs_PointField_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 
 namespace sensor_msgs
 {
@@ -13,52 +13,37 @@
   {
     public:
       char * name;
-      unsigned long offset;
-      unsigned char datatype;
-      unsigned long count;
-      enum { INT8 = 1 };
-      enum { UINT8 = 2 };
-      enum { INT16 = 3 };
-      enum { UINT16 = 4 };
-      enum { INT32 = 5 };
-      enum { UINT32 = 6 };
-      enum { FLOAT32 = 7 };
-      enum { FLOAT64 = 8 };
+      uint32_t offset;
+      uint8_t datatype;
+      uint32_t count;
+      enum { INT8 =  1 };
+      enum { UINT8 =  2 };
+      enum { INT16 =  3 };
+      enum { UINT16 =  4 };
+      enum { INT32 =  5 };
+      enum { UINT32 =  6 };
+      enum { FLOAT32 =  7 };
+      enum { FLOAT64 =  8 };
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
-      long * length_name = (long *)(outbuffer + offset);
+      uint32_t * length_name = (uint32_t *)(outbuffer + offset);
       *length_name = strlen( (const char*) this->name);
       offset += 4;
       memcpy(outbuffer + offset, this->name, *length_name);
       offset += *length_name;
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_offset;
-      u_offset.real = this->offset;
-      *(outbuffer + offset + 0) = (u_offset.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_offset.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_offset.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_offset.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->offset >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->offset >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->offset >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->offset >> (8 * 3)) & 0xFF;
       offset += sizeof(this->offset);
-      union {
-        unsigned char real;
-        unsigned char base;
-      } u_datatype;
-      u_datatype.real = this->datatype;
-      *(outbuffer + offset + 0) = (u_datatype.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->datatype >> (8 * 0)) & 0xFF;
       offset += sizeof(this->datatype);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_count;
-      u_count.real = this->count;
-      *(outbuffer + offset + 0) = (u_count.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_count.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_count.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_count.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->count >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->count >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->count >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->count >> (8 * 3)) & 0xFF;
       offset += sizeof(this->count);
       return offset;
     }
@@ -70,44 +55,27 @@
       offset += 4;
       for(unsigned int k= offset; k< offset+length_name; ++k){
           inbuffer[k-1]=inbuffer[k];
-           }
+      }
       inbuffer[offset+length_name-1]=0;
       this->name = (char *)(inbuffer + offset-1);
       offset += length_name;
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_offset;
-      u_offset.base = 0;
-      u_offset.base |= ((typeof(u_offset.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_offset.base |= ((typeof(u_offset.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_offset.base |= ((typeof(u_offset.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_offset.base |= ((typeof(u_offset.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->offset = u_offset.real;
+      this->offset |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->offset |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->offset |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->offset |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       offset += sizeof(this->offset);
-      union {
-        unsigned char real;
-        unsigned char base;
-      } u_datatype;
-      u_datatype.base = 0;
-      u_datatype.base |= ((typeof(u_datatype.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      this->datatype = u_datatype.real;
+      this->datatype |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
       offset += sizeof(this->datatype);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_count;
-      u_count.base = 0;
-      u_count.base |= ((typeof(u_count.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_count.base |= ((typeof(u_count.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_count.base |= ((typeof(u_count.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_count.base |= ((typeof(u_count.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->count = u_count.real;
+      this->count |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->count |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->count |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->count |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       offset += sizeof(this->count);
      return offset;
     }
 
-   virtual const char * getType(){ return "sensor_msgs/PointField"; };
+    virtual const char * getType(){ return "sensor_msgs/PointField"; };
+    virtual const char * getMD5(){ return "268eacb2962780ceac86cbd17e328150"; };
 
   };
 
--- a/sensor_msgs/Range.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/sensor_msgs/Range.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_Range_h
-#define ros_Range_h
+#ifndef _ROS_sensor_msgs_Range_h
+#define _ROS_sensor_msgs_Range_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "std_msgs/Header.h"
 
 namespace sensor_msgs
@@ -14,7 +14,7 @@
   {
     public:
       std_msgs::Header header;
-      unsigned char radiation_type;
+      uint8_t radiation_type;
       float field_of_view;
       float min_range;
       float max_range;
@@ -22,20 +22,15 @@
       enum { ULTRASOUND = 0 };
       enum { INFRARED = 1 };
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->header.serialize(outbuffer + offset);
-      union {
-        unsigned char real;
-        unsigned char base;
-      } u_radiation_type;
-      u_radiation_type.real = this->radiation_type;
-      *(outbuffer + offset + 0) = (u_radiation_type.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->radiation_type >> (8 * 0)) & 0xFF;
       offset += sizeof(this->radiation_type);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_field_of_view;
       u_field_of_view.real = this->field_of_view;
       *(outbuffer + offset + 0) = (u_field_of_view.base >> (8 * 0)) & 0xFF;
@@ -45,7 +40,7 @@
       offset += sizeof(this->field_of_view);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_min_range;
       u_min_range.real = this->min_range;
       *(outbuffer + offset + 0) = (u_min_range.base >> (8 * 0)) & 0xFF;
@@ -55,7 +50,7 @@
       offset += sizeof(this->min_range);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_max_range;
       u_max_range.real = this->max_range;
       *(outbuffer + offset + 0) = (u_max_range.base >> (8 * 0)) & 0xFF;
@@ -65,7 +60,7 @@
       offset += sizeof(this->max_range);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_range;
       u_range.real = this->range;
       *(outbuffer + offset + 0) = (u_range.base >> (8 * 0)) & 0xFF;
@@ -80,62 +75,57 @@
     {
       int offset = 0;
       offset += this->header.deserialize(inbuffer + offset);
-      union {
-        unsigned char real;
-        unsigned char base;
-      } u_radiation_type;
-      u_radiation_type.base = 0;
-      u_radiation_type.base |= ((typeof(u_radiation_type.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      this->radiation_type = u_radiation_type.real;
+      this->radiation_type |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
       offset += sizeof(this->radiation_type);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_field_of_view;
       u_field_of_view.base = 0;
-      u_field_of_view.base |= ((typeof(u_field_of_view.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_field_of_view.base |= ((typeof(u_field_of_view.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_field_of_view.base |= ((typeof(u_field_of_view.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_field_of_view.base |= ((typeof(u_field_of_view.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       this->field_of_view = u_field_of_view.real;
       offset += sizeof(this->field_of_view);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_min_range;
       u_min_range.base = 0;
-      u_min_range.base |= ((typeof(u_min_range.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_min_range.base |= ((typeof(u_min_range.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_min_range.base |= ((typeof(u_min_range.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_min_range.base |= ((typeof(u_min_range.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       this->min_range = u_min_range.real;
       offset += sizeof(this->min_range);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_max_range;
       u_max_range.base = 0;
-      u_max_range.base |= ((typeof(u_max_range.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_max_range.base |= ((typeof(u_max_range.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_max_range.base |= ((typeof(u_max_range.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_max_range.base |= ((typeof(u_max_range.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       this->max_range = u_max_range.real;
       offset += sizeof(this->max_range);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_range;
       u_range.base = 0;
-      u_range.base |= ((typeof(u_range.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_range.base |= ((typeof(u_range.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_range.base |= ((typeof(u_range.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_range.base |= ((typeof(u_range.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       this->range = u_range.real;
       offset += sizeof(this->range);
      return offset;
     }
 
     virtual const char * getType(){ return "sensor_msgs/Range"; };
+    virtual const char * getMD5(){ return "c005c34273dc426c67a020a87bc24148"; };
 
   };
 
--- a/sensor_msgs/RegionOfInterest.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/sensor_msgs/RegionOfInterest.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_RegionOfInterest_h
-#define ros_RegionOfInterest_h
+#ifndef _ROS_sensor_msgs_RegionOfInterest_h
+#define _ROS_sensor_msgs_RegionOfInterest_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 
 namespace sensor_msgs
 {
@@ -12,58 +12,38 @@
   class RegionOfInterest : public ros::Msg
   {
     public:
-      unsigned long x_offset;
-      unsigned long y_offset;
-      unsigned long height;
-      unsigned long width;
+      uint32_t x_offset;
+      uint32_t y_offset;
+      uint32_t height;
+      uint32_t width;
       bool do_rectify;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_x_offset;
-      u_x_offset.real = this->x_offset;
-      *(outbuffer + offset + 0) = (u_x_offset.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_x_offset.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_x_offset.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_x_offset.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->x_offset >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->x_offset >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->x_offset >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->x_offset >> (8 * 3)) & 0xFF;
       offset += sizeof(this->x_offset);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_y_offset;
-      u_y_offset.real = this->y_offset;
-      *(outbuffer + offset + 0) = (u_y_offset.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_y_offset.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_y_offset.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_y_offset.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->y_offset >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->y_offset >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->y_offset >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->y_offset >> (8 * 3)) & 0xFF;
       offset += sizeof(this->y_offset);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_height;
-      u_height.real = this->height;
-      *(outbuffer + offset + 0) = (u_height.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_height.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_height.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_height.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF;
       offset += sizeof(this->height);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_width;
-      u_width.real = this->width;
-      *(outbuffer + offset + 0) = (u_width.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_width.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_width.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_width.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF;
       offset += sizeof(this->width);
       union {
         bool real;
-        unsigned char base;
+        uint8_t base;
       } u_do_rectify;
       u_do_rectify.real = this->do_rectify;
       *(outbuffer + offset + 0) = (u_do_rectify.base >> (8 * 0)) & 0xFF;
@@ -74,62 +54,39 @@
     virtual int deserialize(unsigned char *inbuffer)
     {
       int offset = 0;
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_x_offset;
-      u_x_offset.base = 0;
-      u_x_offset.base |= ((typeof(u_x_offset.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_x_offset.base |= ((typeof(u_x_offset.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_x_offset.base |= ((typeof(u_x_offset.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_x_offset.base |= ((typeof(u_x_offset.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->x_offset = u_x_offset.real;
+      this->x_offset |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->x_offset |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->x_offset |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->x_offset |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       offset += sizeof(this->x_offset);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_y_offset;
-      u_y_offset.base = 0;
-      u_y_offset.base |= ((typeof(u_y_offset.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_y_offset.base |= ((typeof(u_y_offset.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_y_offset.base |= ((typeof(u_y_offset.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_y_offset.base |= ((typeof(u_y_offset.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->y_offset = u_y_offset.real;
+      this->y_offset |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->y_offset |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->y_offset |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->y_offset |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       offset += sizeof(this->y_offset);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_height;
-      u_height.base = 0;
-      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->height = u_height.real;
+      this->height |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       offset += sizeof(this->height);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_width;
-      u_width.base = 0;
-      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->width = u_width.real;
+      this->width |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
       offset += sizeof(this->width);
       union {
         bool real;
-        unsigned char base;
+        uint8_t base;
       } u_do_rectify;
       u_do_rectify.base = 0;
-      u_do_rectify.base |= ((typeof(u_do_rectify.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_do_rectify.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
       this->do_rectify = u_do_rectify.real;
       offset += sizeof(this->do_rectify);
      return offset;
     }
 
-   virtual const char * getType(){ return "sensor_msgs/RegionOfInterest"; };
+    virtual const char * getType(){ return "sensor_msgs/RegionOfInterest"; };
+    virtual const char * getMD5(){ return "bdb633039d588fcccb441a4d43ccfe09"; };
 
   };
 
--- a/sensor_msgs/SetCameraInfo.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/sensor_msgs/SetCameraInfo.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,9 +1,9 @@
-#ifndef ros_SERVICE_SetCameraInfo_h
-#define ros_SERVICE_SetCameraInfo_h
+#ifndef _ROS_SERVICE_SetCameraInfo_h
+#define _ROS_SERVICE_SetCameraInfo_h
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "sensor_msgs/CameraInfo.h"
 
 namespace sensor_msgs
@@ -16,7 +16,7 @@
     public:
       sensor_msgs::CameraInfo camera_info;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->camera_info.serialize(outbuffer + offset);
@@ -30,7 +30,8 @@
      return offset;
     }
 
-   virtual const char * getType(){ return SETCAMERAINFO; };
+    virtual const char * getType(){ return SETCAMERAINFO; };
+    virtual const char * getMD5(){ return "ee34be01fdeee563d0d99cd594d5581d"; };
 
   };
 
@@ -40,17 +41,17 @@
       bool success;
       char * status_message;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       union {
         bool real;
-        unsigned char base;
+        uint8_t base;
       } u_success;
       u_success.real = this->success;
       *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
       offset += sizeof(this->success);
-      long * length_status_message = (long *)(outbuffer + offset);
+      uint32_t * length_status_message = (uint32_t *)(outbuffer + offset);
       *length_status_message = strlen( (const char*) this->status_message);
       offset += 4;
       memcpy(outbuffer + offset, this->status_message, *length_status_message);
@@ -63,25 +64,32 @@
       int offset = 0;
       union {
         bool real;
-        unsigned char base;
+        uint8_t base;
       } u_success;
       u_success.base = 0;
-      u_success.base |= ((typeof(u_success.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
       this->success = u_success.real;
       offset += sizeof(this->success);
       uint32_t length_status_message = *(uint32_t *)(inbuffer + offset);
       offset += 4;
       for(unsigned int k= offset; k< offset+length_status_message; ++k){
           inbuffer[k-1]=inbuffer[k];
-           }
+      }
       inbuffer[offset+length_status_message-1]=0;
       this->status_message = (char *)(inbuffer + offset-1);
       offset += length_status_message;
      return offset;
     }
 
-   virtual const char * getType(){ return SETCAMERAINFO; };
+    virtual const char * getType(){ return SETCAMERAINFO; };
+    virtual const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; };
+
+  };
 
+  class SetCameraInfo {
+    public:
+    typedef SetCameraInfoRequest Request;
+    typedef SetCameraInfoResponse Response;
   };
 
 }
--- a/std_msgs/Bool.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/Bool.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,49 +1,50 @@
-#ifndef ros_Bool_h
-#define ros_Bool_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-
-namespace std_msgs
-{
-
-  class Bool : public ros::Msg
-  {
-    public:
-      bool data;
-
-    virtual int serialize(unsigned char *outbuffer)
-    {
-      int offset = 0;
-      union {
-        bool real;
-        uint8_t base;
-      } u_data;
-      u_data.real = this->data;
-      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
-      offset += sizeof(this->data);
-      return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer)
-    {
-      int offset = 0;
-      union {
-        bool real;
-        uint8_t base;
-      } u_data;
-      u_data.base = 0;
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      this->data = u_data.real;
-      offset += sizeof(this->data);
-     return offset;
-    }
-
-    virtual const char * getType(){ return "std_msgs/Bool"; };
-
-  };
-
-}
+#ifndef _ROS_std_msgs_Bool_h
+#define _ROS_std_msgs_Bool_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class Bool : public ros::Msg
+  {
+    public:
+      bool data;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_data;
+      u_data.real = this->data;
+      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        bool real;
+        uint8_t base;
+      } u_data;
+      u_data.base = 0;
+      u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->data = u_data.real;
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/Bool"; };
+    virtual const char * getMD5(){ return "8b94c1b53db61fb6aed406028ad6332a"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/Byte.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/Byte.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,49 +1,38 @@
-#ifndef ros_Byte_h
-#define ros_Byte_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-
-namespace std_msgs
-{
-
-  class Byte : public ros::Msg
-  {
-    public:
-      uint8_t data;
-
-    virtual int serialize(unsigned char *outbuffer)
-    {
-      int offset = 0;
-      union {
-        uint8_t real;
-        uint8_t base;
-      } u_data;
-      u_data.real = this->data;
-      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
-      offset += sizeof(this->data);
-      return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer)
-    {
-      int offset = 0;
-      union {
-        uint8_t real;
-        uint8_t base;
-      } u_data;
-      u_data.base = 0;
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      this->data = u_data.real;
-      offset += sizeof(this->data);
-     return offset;
-    }
-
-   virtual const char * getType(){ return "std_msgs/Byte"; };
-
-  };
-
-}
+#ifndef _ROS_std_msgs_Byte_h
+#define _ROS_std_msgs_Byte_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/byte.h"
+
+namespace std_msgs
+{
+
+  class Byte : public ros::Msg
+  {
+    public:
+      std_msgs::byte data;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->data.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->data.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/Byte"; };
+    virtual const char * getMD5(){ return "ad736a2e8818154c487bb80fe42ce43b"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/ByteMultiArray.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/ByteMultiArray.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,69 +1,58 @@
-#ifndef ros_ByteMultiArray_h
-#define ros_ByteMultiArray_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-#include "std_msgs/MultiArrayLayout.h"
-
-namespace std_msgs
-{
-
-  class ByteMultiArray : public ros::Msg
-  {
-    public:
-      std_msgs::MultiArrayLayout layout;
-      uint8_t data_length;
-      uint8_t st_data;
-      uint8_t * data;
-
-    virtual int serialize(unsigned char *outbuffer)
-    {
-      int offset = 0;
-      offset += this->layout.serialize(outbuffer + offset);
-      *(outbuffer + offset++) = data_length;
-      *(outbuffer + offset++) = 0;
-      *(outbuffer + offset++) = 0;
-      *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < data_length; i++){
-      union {
-        uint8_t real;
-        uint8_t base;
-      } u_datai;
-      u_datai.real = this->data[i];
-      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
-      offset += sizeof(this->data[i]);
-      }
-      return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer)
-    {
-      int offset = 0;
-      offset += this->layout.deserialize(inbuffer + offset);
-      unsigned char data_lengthT = *(inbuffer + offset++);
-      if(data_lengthT > data_length)
-        this->data = (unsigned char*)realloc(this->data, data_lengthT * sizeof(unsigned char));
-      offset += 3;
-      data_length = data_lengthT;
-      for( unsigned char i = 0; i < data_length; i++){
-      union {
-        uint8_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);
-      this->st_data = u_st_data.real;
-      offset += sizeof(this->st_data);
-        memcpy( &(this->data[i]), &(this->st_data), sizeof(unsigned char));
-      }
-     return offset;
-    }
-
-   virtual const char * getType(){ return "std_msgs/ByteMultiArray"; };
-
-  };
-
-}
+#ifndef _ROS_std_msgs_ByteMultiArray_h
+#define _ROS_std_msgs_ByteMultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+#include "std_msgs/byte.h"
+
+namespace std_msgs
+{
+
+  class ByteMultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      uint8_t data_length;
+      std_msgs::byte st_data;
+      std_msgs::byte * data;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->layout.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < data_length; i++){
+      offset += this->data[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      uint8_t data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (std_msgs::byte*)realloc(this->data, data_lengthT * sizeof(std_msgs::byte));
+      offset += 3;
+      data_length = data_lengthT;
+      for( uint8_t i = 0; i < data_length; i++){
+      offset += this->st_data.deserialize(inbuffer + offset);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(std_msgs::byte));
+      }
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/ByteMultiArray"; };
+    virtual const char * getMD5(){ return "70ea476cbcfd65ac2f68f3cda1e891fe"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/Char.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/Char.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,49 +1,38 @@
-#ifndef ros_Char_h
-#define ros_Char_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-
-namespace std_msgs
-{
-
-  class Char : public ros::Msg
-  {
-    public:
-      char data;
-
-    virtual int serialize(unsigned char *outbuffer)
-    {
-      int offset = 0;
-      union {
-        char real;
-        unsigned char base;
-      } u_data;
-      u_data.real = this->data;
-      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
-      offset += sizeof(this->data);
-      return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer)
-    {
-      int offset = 0;
-      union {
-        char real;
-        unsigned char base;
-      } u_data;
-      u_data.base = 0;
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      this->data = u_data.real;
-      offset += sizeof(this->data);
-     return offset;
-    }
-
-   virtual const char * getType(){ return "std_msgs/Char"; };
-
-  };
-
-}
+#ifndef _ROS_std_msgs_Char_h
+#define _ROS_std_msgs_Char_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/char.h"
+
+namespace std_msgs
+{
+
+  class Char : public ros::Msg
+  {
+    public:
+      std_msgs::char data;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->data.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->data.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/Char"; };
+    virtual const char * getMD5(){ return "1bf77f25acecdedba0e224b162199717"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/ColorRGBA.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/ColorRGBA.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,121 +1,122 @@
-#ifndef ros_ColorRGBA_h
-#define ros_ColorRGBA_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-
-namespace std_msgs
-{
-
-  class ColorRGBA : public ros::Msg
-  {
-    public:
-      float r;
-      float g;
-      float b;
-      float a;
-
-    virtual int serialize(unsigned char *outbuffer)
-    {
-      int offset = 0;
-      union {
-        float real;
-        uint32_t base;
-      } u_r;
-      u_r.real = this->r;
-      *(outbuffer + offset + 0) = (u_r.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_r.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_r.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_r.base >> (8 * 3)) & 0xFF;
-      offset += sizeof(this->r);
-      union {
-        float real;
-        uint32_t base;
-      } u_g;
-      u_g.real = this->g;
-      *(outbuffer + offset + 0) = (u_g.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_g.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_g.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_g.base >> (8 * 3)) & 0xFF;
-      offset += sizeof(this->g);
-      union {
-        float real;
-        uint32_t base;
-      } u_b;
-      u_b.real = this->b;
-      *(outbuffer + offset + 0) = (u_b.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_b.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_b.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_b.base >> (8 * 3)) & 0xFF;
-      offset += sizeof(this->b);
-      union {
-        float real;
-        uint32_t base;
-      } u_a;
-      u_a.real = this->a;
-      *(outbuffer + offset + 0) = (u_a.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_a.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_a.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_a.base >> (8 * 3)) & 0xFF;
-      offset += sizeof(this->a);
-      return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer)
-    {
-      int offset = 0;
-      union {
-        float real;
-        uint32_t base;
-      } u_r;
-      u_r.base = 0;
-      u_r.base |= ((typeof(u_r.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_r.base |= ((typeof(u_r.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_r.base |= ((typeof(u_r.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_r.base |= ((typeof(u_r.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->r = u_r.real;
-      offset += sizeof(this->r);
-      union {
-        float real;
-        uint32_t base;
-      } u_g;
-      u_g.base = 0;
-      u_g.base |= ((typeof(u_g.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_g.base |= ((typeof(u_g.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_g.base |= ((typeof(u_g.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_g.base |= ((typeof(u_g.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->g = u_g.real;
-      offset += sizeof(this->g);
-      union {
-        float real;
-        uint32_t base;
-      } u_b;
-      u_b.base = 0;
-      u_b.base |= ((typeof(u_b.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_b.base |= ((typeof(u_b.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_b.base |= ((typeof(u_b.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_b.base |= ((typeof(u_b.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->b = u_b.real;
-      offset += sizeof(this->b);
-      union {
-        float real;
-        uint32_t base;
-      } u_a;
-      u_a.base = 0;
-      u_a.base |= ((typeof(u_a.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_a.base |= ((typeof(u_a.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_a.base |= ((typeof(u_a.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_a.base |= ((typeof(u_a.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->a = u_a.real;
-      offset += sizeof(this->a);
-     return offset;
-    }
-
-   virtual const char * getType(){ return "std_msgs/ColorRGBA"; };
-
-  };
-
-}
+#ifndef _ROS_std_msgs_ColorRGBA_h
+#define _ROS_std_msgs_ColorRGBA_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class ColorRGBA : public ros::Msg
+  {
+    public:
+      float r;
+      float g;
+      float b;
+      float a;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        float real;
+        uint32_t base;
+      } u_r;
+      u_r.real = this->r;
+      *(outbuffer + offset + 0) = (u_r.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_r.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_r.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_r.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->r);
+      union {
+        float real;
+        uint32_t base;
+      } u_g;
+      u_g.real = this->g;
+      *(outbuffer + offset + 0) = (u_g.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_g.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_g.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_g.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->g);
+      union {
+        float real;
+        uint32_t base;
+      } u_b;
+      u_b.real = this->b;
+      *(outbuffer + offset + 0) = (u_b.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_b.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_b.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_b.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->b);
+      union {
+        float real;
+        uint32_t base;
+      } u_a;
+      u_a.real = this->a;
+      *(outbuffer + offset + 0) = (u_a.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_a.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_a.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_a.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->a);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        float real;
+        uint32_t base;
+      } u_r;
+      u_r.base = 0;
+      u_r.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_r.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_r.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_r.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->r = u_r.real;
+      offset += sizeof(this->r);
+      union {
+        float real;
+        uint32_t base;
+      } u_g;
+      u_g.base = 0;
+      u_g.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_g.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_g.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_g.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->g = u_g.real;
+      offset += sizeof(this->g);
+      union {
+        float real;
+        uint32_t base;
+      } u_b;
+      u_b.base = 0;
+      u_b.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_b.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_b.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_b.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->b = u_b.real;
+      offset += sizeof(this->b);
+      union {
+        float real;
+        uint32_t base;
+      } u_a;
+      u_a.base = 0;
+      u_a.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_a.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_a.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_a.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->a = u_a.real;
+      offset += sizeof(this->a);
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/ColorRGBA"; };
+    virtual const char * getMD5(){ return "a29a96539573343b1310c73607334b00"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/Duration.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/Duration.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,77 +1,56 @@
-#ifndef ros_Duration_h
-#define ros_Duration_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-#include "ros/duration.h"
-
-namespace std_msgs
-{
-
-  class Duration : public ros::Msg
-  {
-    public:
-      ros::Duration data;
-
-    virtual int serialize(unsigned char *outbuffer)
-    {
-      int offset = 0;
-      union {
-        uint32_t real;
-        uint32_t base;
-      } u_sec;
-      u_sec.real = this->data.sec;
-      *(outbuffer + offset + 0) = (u_sec.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_sec.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_sec.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_sec.base >> (8 * 3)) & 0xFF;
-      offset += sizeof(this->data.sec);
-      union {
-        uint32_t real;
-        uint32_t base;
-      } u_nsec;
-      u_nsec.real = this->data.nsec;
-      *(outbuffer + offset + 0) = (u_nsec.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_nsec.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_nsec.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_nsec.base >> (8 * 3)) & 0xFF;
-      offset += sizeof(this->data.nsec);
-      return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer)
-    {
-      int offset = 0;
-      union {
-        uint32_t real;
-        uint32_t base;
-      } u_sec;
-      u_sec.base = 0;
-      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->data.sec = u_sec.real;
-      offset += sizeof(this->data.sec);
-      union {
-        uint32_t real;
-        uint32_t base;
-      } u_nsec;
-      u_nsec.base = 0;
-      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->data.nsec = u_nsec.real;
-      offset += sizeof(this->data.nsec);
-     return offset;
-    }
-
-   virtual const char * getType(){ return "std_msgs/Duration"; };
-
-  };
-
-}
+#ifndef _ROS_std_msgs_Duration_h
+#define _ROS_std_msgs_Duration_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "ros/duration.h"
+
+namespace std_msgs
+{
+
+  class Duration : public ros::Msg
+  {
+    public:
+      ros::Duration data;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->data.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data.sec);
+      *(outbuffer + offset + 0) = (this->data.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data.nsec);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->data.sec |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->data.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->data.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->data.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->data.sec);
+      this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->data.nsec);
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/Duration"; };
+    virtual const char * getMD5(){ return "3e286caf4241d664e55f3ad380e2ae46"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/Empty.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/Empty.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,31 +1,34 @@
-#ifndef ros_Empty_h
-#define ros_Empty_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-
-namespace std_msgs {
-
-class Empty : public ros::Msg {
-public:
-
-    virtual int serialize(unsigned char *outbuffer) {
-        int offset = 0;
-        return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer) {
-        int offset = 0;
-        return offset;
-    }
-
-    virtual const char * getType() {
-        return "std_msgs/Empty";
-    };
-
-};
-
-}
+#ifndef _ROS_std_msgs_Empty_h
+#define _ROS_std_msgs_Empty_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class Empty : public ros::Msg
+  {
+    public:
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/Empty"; };
+    virtual const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/Float32.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/Float32.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,55 +1,56 @@
-#ifndef ros_Float32_h
-#define ros_Float32_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-
-namespace std_msgs
-{
-
-  class Float32 : public ros::Msg
-  {
-    public:
-      float data;
-
-    virtual int serialize(unsigned char *outbuffer)
-    {
-      int offset = 0;
-      union {
-        float real;
-        uint32_t base;
-      } u_data;
-      u_data.real = this->data;
-      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF;
-      offset += sizeof(this->data);
-      return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer)
-    {
-      int offset = 0;
-      union {
-        float real;
-        uint32_t base;
-      } u_data;
-      u_data.base = 0;
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->data = u_data.real;
-      offset += sizeof(this->data);
-     return offset;
-    }
-
-    virtual const char * getType(){ return "std_msgs/Float32"; };
-
-  };
-
-}
+#ifndef _ROS_std_msgs_Float32_h
+#define _ROS_std_msgs_Float32_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class Float32 : public ros::Msg
+  {
+    public:
+      float data;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        float real;
+        uint32_t base;
+      } u_data;
+      u_data.real = this->data;
+      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        float real;
+        uint32_t base;
+      } u_data;
+      u_data.base = 0;
+      u_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->data = u_data.real;
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/Float32"; };
+    virtual const char * getMD5(){ return "73fcbf46b49191e672908e50842a83d4"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/Float32MultiArray.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/Float32MultiArray.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,73 +1,76 @@
-#ifndef ros_Float32MultiArray_h
-#define ros_Float32MultiArray_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-#include "std_msgs/MultiArrayLayout.h"
-
-namespace std_msgs {
-
-class Float32MultiArray : public ros::Msg {
-public:
-    std_msgs::MultiArrayLayout layout;
-    unsigned char data_length;
-    float st_data;
-    float * data;
-
-    virtual int serialize(unsigned char *outbuffer) {
-        int offset = 0;
-        offset += this->layout.serialize(outbuffer + offset);
-        *(outbuffer + offset++) = data_length;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        for ( unsigned char i = 0; i < data_length; i++) {
-            union {
-                float real;
-                uint32_t base;
-            } u_datai;
-            u_datai.real = this->data[i];
-            *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
-            *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF;
-            *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF;
-            *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF;
-            offset += sizeof(this->data[i]);
-        }
-        return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer) {
-        int offset = 0;
-        offset += this->layout.deserialize(inbuffer + offset);
-        unsigned char data_lengthT = *(inbuffer + offset++);
-        if (data_lengthT > data_length)
-            this->data = (float*)realloc(this->data, data_lengthT * sizeof(float));
-        offset += 3;
-        data_length = data_lengthT;
-        for ( unsigned char i = 0; i < data_length; i++) {
-            union {
-                float real;
-                uint32_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 |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-            this->st_data = u_st_data.real;
-            offset += sizeof(this->st_data);
-            memcpy( &(this->data[i]), &(this->st_data), sizeof(float));
-        }
-        return offset;
-    }
-
-    virtual const char * getType() {
-        return "std_msgs/Float32MultiArray";
-    };
-
-};
-
-}
+#ifndef _ROS_std_msgs_Float32MultiArray_h
+#define _ROS_std_msgs_Float32MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class Float32MultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      uint8_t data_length;
+      float st_data;
+      float * data;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->layout.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        float real;
+        uint32_t base;
+      } u_datai;
+      u_datai.real = this->data[i];
+      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      uint8_t data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (float*)realloc(this->data, data_lengthT * sizeof(float));
+      offset += 3;
+      data_length = data_lengthT;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        float real;
+        uint32_t base;
+      } u_st_data;
+      u_st_data.base = 0;
+      u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->st_data = u_st_data.real;
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(float));
+      }
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/Float32MultiArray"; };
+    virtual const char * getMD5(){ return "6a40e0ffa6a17a503ac3f8616991b1f6"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/Float64.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/Float64.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,100 +1,64 @@
-#ifndef ros_Float64_h
-#define ros_Float64_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-
-namespace std_msgs
-{
-
-  class Float64 : public ros::Msg
-  {
-    public:
-      double data;
-
-    virtual int serialize(unsigned char *outbuffer)
-    {
-      int offset = 0;
-      union {
-        double real;
-        uint64_t base;
-      } u_data;
-      u_data.real = this->data;
-      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF;
-      *(outbuffer + offset + 4) = (u_data.base >> (8 * 4)) & 0xFF;
-      *(outbuffer + offset + 5) = (u_data.base >> (8 * 5)) & 0xFF;
-      *(outbuffer + offset + 6) = (u_data.base >> (8 * 6)) & 0xFF;
-      *(outbuffer + offset + 7) = (u_data.base >> (8 * 7)) & 0xFF;
-      offset += sizeof(this->data);
-      return offset;
-    }
-    
-    virtual int deserialize(unsigned char *inbuffer)
-    {
-      int offset = 0;
-      union {
-        double real;
-        uint64_t base;
-      } u_data;
-      u_data.base = 0;
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 4))) << (8 * 4);
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 5))) << (8 * 5);
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 6))) << (8 * 6);
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 7))) << (8 * 7);
-      this->data = u_data.real;
-      offset += sizeof(this->data);
-     return offset;
-    }
-/*
-    virtual int serialize(unsigned char *outbuffer)
-    {
-      int offset = 0;
-      long * val_data = (long *) &(this->data);
-      long exp_data = (((*val_data)>>23)&255);
-      if(exp_data != 0)
-        exp_data += 1023-127;
-      long sig_data = *val_data;
-      *(outbuffer + offset++) = 0;
-      *(outbuffer + offset++) = 0;
-      *(outbuffer + offset++) = 0;
-      *(outbuffer + offset++) = (sig_data<<5) & 0xff;
-      *(outbuffer + offset++) = (sig_data>>3) & 0xff;
-      *(outbuffer + offset++) = (sig_data>>11) & 0xff;
-      *(outbuffer + offset++) = ((exp_data<<4) & 0xF0) | ((sig_data>>19)&0x0F);
-      *(outbuffer + offset++) = (exp_data>>4) & 0x7F;
-      if(this->data < 0) *(outbuffer + offset -1) |= 0x80;
-      return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer)
-    {
-      int offset = 0;
-      unsigned long * val_data = (unsigned long*) &(this->data);
-      offset += 3;
-      *val_data = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-      *val_data |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-      *val_data |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-      *val_data |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-      unsigned long exp_data = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-      exp_data |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
-      if(exp_data !=0)
-        *val_data |= ((exp_data)-1023+127)<<23;
-      if( ((*(inbuffer+offset++)) & 0x80) > 0) this->data = -this->data;
-     return offset;
-    }
-*/
-    virtual const char * getType(){ return "std_msgs/Float64"; };
-
-  };
-
-}
+#ifndef _ROS_std_msgs_Float64_h
+#define _ROS_std_msgs_Float64_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class Float64 : public ros::Msg
+  {
+    public:
+      double data;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_data;
+      u_data.real = this->data;
+      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset + 4) = (u_data.base >> (8 * 4)) & 0xFF;
+      *(outbuffer + offset + 5) = (u_data.base >> (8 * 5)) & 0xFF;
+      *(outbuffer + offset + 6) = (u_data.base >> (8 * 6)) & 0xFF;
+      *(outbuffer + offset + 7) = (u_data.base >> (8 * 7)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+    
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        double real;
+        uint64_t base;
+      } u_data;
+      u_data.base = 0;
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 4))) << (8 * 4);
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 5))) << (8 * 5);
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 6))) << (8 * 6);
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 7))) << (8 * 7);
+      this->data = u_data.real;
+      offset += sizeof(this->data);
+     return offset;
+    }
+    
+    virtual const char * getType(){ return "std_msgs/Float64"; };
+    virtual const char * getMD5(){ return "fdb28210bfa9d7c91146260178d9a584"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/Float64MultiArray.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/Float64MultiArray.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,141 +1,83 @@
-#ifndef ros_Float64MultiArray_h
-#define ros_Float64MultiArray_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-#include "std_msgs/MultiArrayLayout.h"
-
-namespace std_msgs {
-
-class Float64MultiArray : public ros::Msg {
-public:
-    std_msgs::MultiArrayLayout layout;
-    unsigned char data_length;
-    double st_data;
-    double * data;
-
-    virtual int serialize(unsigned char *outbuffer) {
-        int offset = 0;
-        offset += this->layout.serialize(outbuffer + offset);
-        *(outbuffer + offset++) = data_length;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        for ( unsigned char i = 0; i < data_length; i++) {
-            union {
-                double real;
-                uint64_t base;
-            } u_datai;
-            u_datai.real = this->data[i];
-            *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
-            *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF;
-            *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF;
-            *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF;
-            *(outbuffer + offset + 4) = (u_datai.base >> (8 * 4)) & 0xFF;
-            *(outbuffer + offset + 5) = (u_datai.base >> (8 * 5)) & 0xFF;
-            *(outbuffer + offset + 6) = (u_datai.base >> (8 * 6)) & 0xFF;
-            *(outbuffer + offset + 7) = (u_datai.base >> (8 * 7)) & 0xFF;
-            offset += sizeof(this->data[i]);
-        }
-        return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer) {
-        int offset = 0;
-        offset += this->layout.deserialize(inbuffer + offset);
-        unsigned char data_lengthT = *(inbuffer + offset++);
-        if (data_lengthT > data_length)
-            this->data = (double*)realloc(this->data, data_lengthT * sizeof(double));
-        offset += 3;
-        data_length = data_lengthT;
-        for ( unsigned char i = 0; i < data_length; i++) {
-            union {
-                double real;
-                uint64_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 |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 4))) << (8 * 4);
-            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 5))) << (8 * 5);
-            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 6))) << (8 * 6);
-            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 7))) << (8 * 7);
-            this->st_data = u_st_data.real;
-            offset += sizeof(this->st_data);
-            memcpy( &(this->data[i]), &(this->st_data), sizeof(double));
-        }
-        return offset;
-    }
-
-    /*
-      public:
-        std_msgs::MultiArrayLayout layout;
-        unsigned char data_length;
-        float st_data;
-        float * data;
-
-      virtual int serialize(unsigned char *outbuffer)
-      {
-        int offset = 0;
-        offset += this->layout.serialize(outbuffer + offset);
-        *(outbuffer + offset++) = data_length;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        for( unsigned char i = 0; i < data_length; i++){
-        long * val_datai = (long *) &(this->data[i]);
-        long exp_datai = (((*val_datai)>>23)&255);
-        if(exp_datai != 0)
-          exp_datai += 1023-127;
-        long sig_datai = *val_datai;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = (sig_datai<<5) & 0xff;
-        *(outbuffer + offset++) = (sig_datai>>3) & 0xff;
-        *(outbuffer + offset++) = (sig_datai>>11) & 0xff;
-        *(outbuffer + offset++) = ((exp_datai<<4) & 0xF0) | ((sig_datai>>19)&0x0F);
-        *(outbuffer + offset++) = (exp_datai>>4) & 0x7F;
-        if(this->data[i] < 0) *(outbuffer + offset -1) |= 0x80;
-        }
-        return offset;
-      }
-
-      virtual int deserialize(unsigned char *inbuffer)
-      {
-        int offset = 0;
-        offset += this->layout.deserialize(inbuffer + offset);
-        unsigned char data_lengthT = *(inbuffer + offset++);
-        if(data_lengthT > data_length)
-          this->data = (float*)realloc(this->data, data_lengthT * sizeof(float));
-        offset += 3;
-        data_length = data_lengthT;
-        for( unsigned char i = 0; i < data_length; i++){
-        unsigned long * val_st_data = (unsigned long*) &(this->st_data);
-        offset += 3;
-        *val_st_data = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
-        *val_st_data |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
-        *val_st_data |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
-        *val_st_data |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
-        unsigned long exp_st_data = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
-        exp_st_data |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
-        if(exp_st_data !=0)
-          *val_st_data |= ((exp_st_data)-1023+127)<<23;
-        if( ((*(inbuffer+offset++)) & 0x80) > 0) this->st_data = -this->st_data;
-          memcpy( &(this->data[i]), &(this->st_data), sizeof(float));
-        }
-       return offset;
-      }
-    */
-    virtual const char * getType() {
-        return "std_msgs/Float64MultiArray";
-    };
-
-};
-
-}
+#ifndef _ROS_std_msgs_Float64MultiArray_h
+#define _ROS_std_msgs_Float64MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class Float64MultiArray : public ros::Msg
+  {
+public:
+    std_msgs::MultiArrayLayout layout;
+    unsigned char data_length;
+    double st_data;
+    double * data;
+
+    virtual int serialize(unsigned char *outbuffer) const
+     {
+        int offset = 0;
+        offset += this->layout.serialize(outbuffer + offset);
+        *(outbuffer + offset++) = data_length;
+        *(outbuffer + offset++) = 0;
+        *(outbuffer + offset++) = 0;
+        *(outbuffer + offset++) = 0;
+        for ( unsigned char i = 0; i < data_length; i++) {
+            union {
+                double real;
+                uint64_t base;
+            } u_datai;
+            u_datai.real = this->data[i];
+            *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+            *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF;
+            *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF;
+            *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF;
+            *(outbuffer + offset + 4) = (u_datai.base >> (8 * 4)) & 0xFF;
+            *(outbuffer + offset + 5) = (u_datai.base >> (8 * 5)) & 0xFF;
+            *(outbuffer + offset + 6) = (u_datai.base >> (8 * 6)) & 0xFF;
+            *(outbuffer + offset + 7) = (u_datai.base >> (8 * 7)) & 0xFF;
+            offset += sizeof(this->data[i]);
+        }
+        return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer) {
+        int offset = 0;
+        offset += this->layout.deserialize(inbuffer + offset);
+        unsigned char data_lengthT = *(inbuffer + offset++);
+        if (data_lengthT > data_length)
+            this->data = (double*)realloc(this->data, data_lengthT * sizeof(double));
+        offset += 3;
+        data_length = data_lengthT;
+        for ( unsigned char i = 0; i < data_length; i++) {
+            union {
+                double real;
+                uint64_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 |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 4))) << (8 * 4);
+            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 5))) << (8 * 5);
+            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 6))) << (8 * 6);
+            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 7))) << (8 * 7);
+            this->st_data = u_st_data.real;
+            offset += sizeof(this->st_data);
+            memcpy( &(this->data[i]), &(this->st_data), sizeof(double));
+        }
+        return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/Float64MultiArray"; };
+    virtual const char * getMD5(){ return "4b7d974086d4060e7db4613a7e6c3ba4"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/Header.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/Header.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,113 +1,81 @@
-#ifndef ros_std_msgs_Header_h
-#define ros_std_msgs_Header_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-#include "ros/time.h"
-
-namespace std_msgs
-{
-
-  class Header : public ros::Msg
-  {
-    public:
-      unsigned long seq;
-      ros::Time stamp;
-      char * frame_id;
-
-    virtual int serialize(unsigned char *outbuffer)
-    {
-      int offset = 0;
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_seq;
-      u_seq.real = this->seq;
-      *(outbuffer + offset + 0) = (u_seq.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_seq.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_seq.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_seq.base >> (8 * 3)) & 0xFF;
-      offset += sizeof(this->seq);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_sec;
-      u_sec.real = this->stamp.sec;
-      *(outbuffer + offset + 0) = (u_sec.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_sec.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_sec.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_sec.base >> (8 * 3)) & 0xFF;
-      offset += sizeof(this->stamp.sec);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_nsec;
-      u_nsec.real = this->stamp.nsec;
-      *(outbuffer + offset + 0) = (u_nsec.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_nsec.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_nsec.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_nsec.base >> (8 * 3)) & 0xFF;
-      offset += sizeof(this->stamp.nsec);
-      long * length_frame_id = (long *)(outbuffer + offset);
-      *length_frame_id = strlen( (const char*) this->frame_id);
-      offset += 4;
-      memcpy(outbuffer + offset, this->frame_id, *length_frame_id);
-      offset += *length_frame_id;
-      return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer)
-    {
-      int offset = 0;
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_seq;
-      u_seq.base = 0;
-      u_seq.base |= ((typeof(u_seq.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_seq.base |= ((typeof(u_seq.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_seq.base |= ((typeof(u_seq.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_seq.base |= ((typeof(u_seq.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->seq = u_seq.real;
-      offset += sizeof(this->seq);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_sec;
-      u_sec.base = 0;
-      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->stamp.sec = u_sec.real;
-      offset += sizeof(this->stamp.sec);
-      union {
-        unsigned long real;
-        unsigned long base;
-      } u_nsec;
-      u_nsec.base = 0;
-      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->stamp.nsec = u_nsec.real;
-      offset += sizeof(this->stamp.nsec);
-      uint32_t length_frame_id = *(uint32_t *)(inbuffer + offset);
-      offset += 4;
-      for(unsigned int k= offset; k< offset+length_frame_id; ++k){
-          inbuffer[k-1]=inbuffer[k];
-           }
-      inbuffer[offset+length_frame_id-1]=0;
-      this->frame_id = (char *)(inbuffer + offset-1);
-      offset += length_frame_id;
-     return offset;
-    }
-
-    const char * getType(){ return "std_msgs/Header"; };
-
-  };
-
-}
+#ifndef _ROS_std_msgs_Header_h
+#define _ROS_std_msgs_Header_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "ros/time.h"
+
+namespace std_msgs
+{
+
+  class Header : public ros::Msg
+  {
+    public:
+      uint32_t seq;
+      ros::Time stamp;
+      char * frame_id;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->seq >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->seq >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->seq >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->seq >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->seq);
+      *(outbuffer + offset + 0) = (this->stamp.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->stamp.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->stamp.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->stamp.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->stamp.sec);
+      *(outbuffer + offset + 0) = (this->stamp.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->stamp.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->stamp.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->stamp.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->stamp.nsec);
+      uint32_t * length_frame_id = (uint32_t *)(outbuffer + offset);
+      *length_frame_id = strlen( (const char*) this->frame_id);
+      offset += 4;
+      memcpy(outbuffer + offset, this->frame_id, *length_frame_id);
+      offset += *length_frame_id;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->seq |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->seq |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->seq |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->seq |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->seq);
+      this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->stamp.sec);
+      this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->stamp.nsec);
+      uint32_t length_frame_id = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_frame_id; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_frame_id-1]=0;
+      this->frame_id = (char *)(inbuffer + offset-1);
+      offset += length_frame_id;
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/Header"; };
+    virtual const char * getMD5(){ return "2176decaecbce78abc3b96ef049fabed"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/Int16.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/Int16.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,51 +1,52 @@
-#ifndef ros_Int16_h
-#define ros_Int16_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-
-namespace std_msgs
-{
-
-  class Int16 : public ros::Msg
-  {
-    public:
-      int16_t data;
-
-    virtual int serialize(unsigned char *outbuffer)
-    {
-      int offset = 0;
-      union {
-        int16_t;
-        uint16_t base;
-      } u_data;
-      u_data.real = this->data;
-      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF;
-      offset += sizeof(this->data);
-      return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer)
-    {
-      int offset = 0;
-      union {
-        int16_t real;
-        uint16_t base;
-      } u_data;
-      u_data.base = 0;
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      this->data = u_data.real;
-      offset += sizeof(this->data);
-     return offset;
-    }
-
-   virtual const char * getType(){ return "std_msgs/Int16"; };
-
-  };
-
-}
+#ifndef _ROS_std_msgs_Int16_h
+#define _ROS_std_msgs_Int16_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class Int16 : public ros::Msg
+  {
+    public:
+      int16_t data;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int16_t real;
+        uint16_t base;
+      } u_data;
+      u_data.real = this->data;
+      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int16_t real;
+        uint16_t base;
+      } u_data;
+      u_data.base = 0;
+      u_data.base |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_data.base |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->data = u_data.real;
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/Int16"; };
+    virtual const char * getMD5(){ return "8524586e34fbd7cb1c08c5f5f1ca0e57"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/Int16MultiArray.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/Int16MultiArray.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,71 +1,72 @@
-#ifndef ros_Int16MultiArray_h
-#define ros_Int16MultiArray_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-#include "std_msgs/MultiArrayLayout.h"
-
-namespace std_msgs
-{
-
-  class Int16MultiArray : public ros::Msg
-  {
-    public:
-      std_msgs::MultiArrayLayout layout;
-      unsigned char data_length;
-      int16_t st_data;
-      int16_t * data;
-
-    virtual int serialize(unsigned char *outbuffer)
-    {
-      int offset = 0;
-      offset += this->layout.serialize(outbuffer + offset);
-      *(outbuffer + offset++) = data_length;
-      *(outbuffer + offset++) = 0;
-      *(outbuffer + offset++) = 0;
-      *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < data_length; i++){
-      union {
-        int16_t real;
-        uint16_t base;
-      } u_datai;
-      u_datai.real = this->data[i];
-      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF;
-      offset += sizeof(this->data[i]);
-      }
-      return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer)
-    {
-      int offset = 0;
-      offset += this->layout.deserialize(inbuffer + offset);
-      unsigned char data_lengthT = *(inbuffer + offset++);
-      if(data_lengthT > data_length)
-        this->data = (int16_t*)realloc(this->data, data_lengthT * sizeof(int16_t));
-      offset += 3;
-      data_length = data_lengthT;
-      for( unsigned char i = 0; i < data_length; i++){
-      union {
-        int16_t real;
-        uint16_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 |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      this->st_data = u_st_data.real;
-      offset += sizeof(this->st_data);
-        memcpy( &(this->data[i]), &(this->st_data), sizeof(int16_t));
-      }
-     return offset;
-    }
-
-   virtual const char * getType(){ return "std_msgs/Int16MultiArray"; };
-
-  };
-
-}
+#ifndef _ROS_std_msgs_Int16MultiArray_h
+#define _ROS_std_msgs_Int16MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class Int16MultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      uint8_t data_length;
+      int16_t st_data;
+      int16_t * data;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->layout.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        int16_t real;
+        uint16_t base;
+      } u_datai;
+      u_datai.real = this->data[i];
+      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      uint8_t data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (int16_t*)realloc(this->data, data_lengthT * sizeof(int16_t));
+      offset += 3;
+      data_length = data_lengthT;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        int16_t real;
+        uint16_t base;
+      } u_st_data;
+      u_st_data.base = 0;
+      u_st_data.base |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_data.base |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->st_data = u_st_data.real;
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(int16_t));
+      }
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/Int16MultiArray"; };
+    virtual const char * getMD5(){ return "d9338d7f523fcb692fae9d0a0e9f067c"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/Int32.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/Int32.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,55 +1,56 @@
-#ifndef ros_Int32_h
-#define ros_Int32_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-
-namespace std_msgs
-{
-
-  class Int32 : public ros::Msg
-  {
-    public:
-      int32_t data;
-
-    virtual int serialize(unsigned char *outbuffer)
-    {
-      int offset = 0;
-      union {
-        int32_t real;
-        uint32_t base;
-      } u_data;
-      u_data.real = this->data;
-      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF;
-      offset += sizeof(this->data);
-      return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer)
-    {
-      int offset = 0;
-      union {
-        int32_t real;
-        uint32_t base;
-      } u_data;
-      u_data.base = 0;
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->data = u_data.real;
-      offset += sizeof(this->data);
-     return offset;
-    }
-
-   virtual const char * getType(){ return "std_msgs/Int32"; };
-
-  };
-
-}
+#ifndef _ROS_std_msgs_Int32_h
+#define _ROS_std_msgs_Int32_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class Int32 : public ros::Msg
+  {
+    public:
+      int32_t data;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_data;
+      u_data.real = this->data;
+      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_data;
+      u_data.base = 0;
+      u_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->data = u_data.real;
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/Int32"; };
+    virtual const char * getMD5(){ return "da5909fbe378aeaf85e547e830cc1bb7"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/Int32MultiArray.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/Int32MultiArray.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,75 +1,76 @@
-#ifndef ros_Int32MultiArray_h
-#define ros_Int32MultiArray_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-#include "std_msgs/MultiArrayLayout.h"
-
-namespace std_msgs
-{
-
-  class Int32MultiArray : public ros::Msg
-  {
-    public:
-      std_msgs::MultiArrayLayout layout;
-      unsigned char data_length;
-      int32_t st_data;
-      int32_t * data;
-
-    virtual int serialize(unsigned char *outbuffer)
-    {
-      int offset = 0;
-      offset += this->layout.serialize(outbuffer + offset);
-      *(outbuffer + offset++) = data_length;
-      *(outbuffer + offset++) = 0;
-      *(outbuffer + offset++) = 0;
-      *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < data_length; i++){
-      union {
-        int32_t real;
-        uint32_t base;
-      } u_datai;
-      u_datai.real = this->data[i];
-      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF;
-      offset += sizeof(this->data[i]);
-      }
-      return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer)
-    {
-      int offset = 0;
-      offset += this->layout.deserialize(inbuffer + offset);
-      unsigned char data_lengthT = *(inbuffer + offset++);
-      if(data_lengthT > data_length)
-        this->data = (int32_t*)realloc(this->data, data_lengthT * sizeof(int32_t));
-      offset += 3;
-      data_length = data_lengthT;
-      for( unsigned char i = 0; i < data_length; i++){
-      union {
-        int32_t real;
-        uint32_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 |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->st_data = u_st_data.real;
-      offset += sizeof(this->st_data);
-        memcpy( &(this->data[i]), &(this->st_data), sizeof(int32_t));
-      }
-     return offset;
-    }
-
-   virtual const char * getType(){ return "std_msgs/Int32MultiArray"; };
-
-  };
-
-}
+#ifndef _ROS_std_msgs_Int32MultiArray_h
+#define _ROS_std_msgs_Int32MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class Int32MultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      uint8_t data_length;
+      int32_t st_data;
+      int32_t * data;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->layout.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_datai;
+      u_datai.real = this->data[i];
+      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      uint8_t data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (int32_t*)realloc(this->data, data_lengthT * sizeof(int32_t));
+      offset += 3;
+      data_length = data_lengthT;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        int32_t real;
+        uint32_t base;
+      } u_st_data;
+      u_st_data.base = 0;
+      u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->st_data = u_st_data.real;
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(int32_t));
+      }
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/Int32MultiArray"; };
+    virtual const char * getMD5(){ return "1d99f79f8b325b44fee908053e9c945b"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/Int64.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/Int64.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,93 +1,66 @@
-#ifndef ros_Int64_h
-#define ros_Int64_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-
-namespace std_msgs {
-
-class Int64 : public ros::Msg {
-public:
-    int64_t data;
-
-    virtual int serialize(unsigned char *outbuffer) {
-        int offset = 0;
-        union {
-            int64_t real;
-            uint64_t base;
-        } u_data;
-        u_data.real = this->data;
-        *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
-        *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF;
-        *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF;
-        *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF;
-        *(outbuffer + offset + 4) = (u_data.base >> (8 * 4)) & 0xFF;
-        *(outbuffer + offset + 5) = (u_data.base >> (8 * 5)) & 0xFF;
-        *(outbuffer + offset + 6) = (u_data.base >> (8 * 6)) & 0xFF;
-        *(outbuffer + offset + 7) = (u_data.base >> (8 * 7)) & 0xFF;        
-        
-        offset += sizeof(this->data);
-        return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer) {
-        int offset = 0;
-        union {
-            int64_t real;
-            uint64_t base;
-        } u_data;
-        u_data.base = 0;
-        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 4))) << (8 * 4);
-        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 5))) << (8 * 5);
-        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 6))) << (8 * 6);
-        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 7))) << (8 * 7);
-        
-        this->data = u_data.real;
-        offset += sizeof(this->data);
-        return offset;
-    }
-    /*
-      public:
-        long data;
-
-      virtual int serialize(unsigned char *outbuffer)
-      {
-        int offset = 0;
-        *(outbuffer + offset++) = (data >> (8 * 0)) & 0xFF;
-        *(outbuffer + offset++) = (data >> (8 * 1)) & 0xFF;
-        *(outbuffer + offset++) = (data >> (8 * 2)) & 0xFF;
-        *(outbuffer + offset++) = (data >> (8 * 3)) & 0xFF;
-        *(outbuffer + offset++) = (data > 0) ? 0: 255;
-        *(outbuffer + offset++) = (data > 0) ? 0: 255;
-        *(outbuffer + offset++) = (data > 0) ? 0: 255;
-        *(outbuffer + offset++) = (data > 0) ? 0: 255;
-        return offset;
-      }
-
-      virtual int deserialize(unsigned char *inbuffer)
-      {
-        int offset = 0;
-        data = 0;
-        data += ((long)(*(inbuffer + offset++))) >> (8 * 0);
-        data += ((long)(*(inbuffer + offset++))) >> (8 * 1);
-        data += ((long)(*(inbuffer + offset++))) >> (8 * 2);
-        data += ((long)(*(inbuffer + offset++))) >> (8 * 3);
-        offset += 4;
-       return offset;
-      }
-      */
-
-    virtual const char * getType() {
-        return "std_msgs/Int64";
-    };
-
-};
-
-}
+#ifndef _ROS_std_msgs_Int64_h
+#define _ROS_std_msgs_Int64_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs {
+
+class Int64 : public ros::Msg {
+public:
+    int64_t data;
+
+    virtual int serialize(unsigned char *outbuffer) const {
+        int offset = 0;
+        union {
+            int64_t real;
+            uint64_t base;
+        } u_data;
+        u_data.real = this->data;
+        *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+        *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF;
+        *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF;
+        *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF;
+        *(outbuffer + offset + 4) = (u_data.base >> (8 * 4)) & 0xFF;
+        *(outbuffer + offset + 5) = (u_data.base >> (8 * 5)) & 0xFF;
+        *(outbuffer + offset + 6) = (u_data.base >> (8 * 6)) & 0xFF;
+        *(outbuffer + offset + 7) = (u_data.base >> (8 * 7)) & 0xFF;
+
+        offset += sizeof(this->data);
+        return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer) {
+        int offset = 0;
+        union {
+            int64_t real;
+            uint64_t base;
+        } u_data;
+        u_data.base = 0;
+        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 4))) << (8 * 4);
+        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 5))) << (8 * 5);
+        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 6))) << (8 * 6);
+        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 7))) << (8 * 7);
+
+        this->data = u_data.real;
+        offset += sizeof(this->data);
+        return offset;
+    }
+
+    virtual const char * getType() {
+        return "std_msgs/Int64";
+    };
+    virtual const char * getMD5() {
+        return "34add168574510e6e17f5d23ecc077ef";
+    };
+
+};
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/Int64MultiArray.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/Int64MultiArray.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,128 +1,84 @@
-#ifndef ros_Int64MultiArray_h
-#define ros_Int64MultiArray_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-#include "std_msgs/MultiArrayLayout.h"
-
-namespace std_msgs {
-
-class Int64MultiArray : public ros::Msg {
-public:
-    std_msgs::MultiArrayLayout layout;
-    unsigned char data_length;
-    int64_t st_data;
-    int64_t * data;
-
-    virtual int serialize(unsigned char *outbuffer) {
-        int offset = 0;
-        offset += this->layout.serialize(outbuffer + offset);
-        *(outbuffer + offset++) = data_length;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        for ( unsigned char i = 0; i < data_length; i++) {
-            union {
-                int64_t real;
-                uint64_t base;
-            } u_datai;
-            u_datai.real = this->data[i];
-            *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
-            *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF;
-            *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF;
-            *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF;
-            *(outbuffer + offset + 4) = (u_datai.base >> (8 * 4)) & 0xFF;
-            *(outbuffer + offset + 5) = (u_datai.base >> (8 * 5)) & 0xFF;
-            *(outbuffer + offset + 6) = (u_datai.base >> (8 * 6)) & 0xFF;
-            *(outbuffer + offset + 7) = (u_datai.base >> (8 * 7)) & 0xFF;
-            offset += sizeof(this->data[i]);
-        }
-        return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer) {
-        int offset = 0;
-        offset += this->layout.deserialize(inbuffer + offset);
-        unsigned char data_lengthT = *(inbuffer + offset++);
-        if (data_lengthT > data_length)
-            this->data = (int64_t*)realloc(this->data, data_lengthT * sizeof(int64_t));
-        offset += 3;
-        data_length = data_lengthT;
-        for ( unsigned char i = 0; i < data_length; i++) {
-            union {
-                int64_t real;
-                uint64_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 |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 4))) << (8 * 4);
-            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 5))) << (8 * 5);
-            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 6))) << (8 * 6);
-            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 7))) << (8 * 7);
-            this->st_data = u_st_data.real;
-            offset += sizeof(this->st_data);
-            memcpy( &(this->data[i]), &(this->st_data), sizeof(int64_t));
-        }
-        return offset;
-    }
-    /*
-    public:
-        std_msgs::MultiArrayLayout layout;
-        unsigned char data_length;
-        long st_data;
-        long * data;
-
-        virtual int serialize(unsigned char *outbuffer) {
-            int offset = 0;
-            offset += this->layout.serialize(outbuffer + offset);
-            *(outbuffer + offset++) = data_length;
-            *(outbuffer + offset++) = 0;
-            *(outbuffer + offset++) = 0;
-            *(outbuffer + offset++) = 0;
-            for ( unsigned char i = 0; i < data_length; i++) {
-                *(outbuffer + offset++) = (data[i] >> (8 * 0)) & 0xFF;
-                *(outbuffer + offset++) = (data[i] >> (8 * 1)) & 0xFF;
-                *(outbuffer + offset++) = (data[i] >> (8 * 2)) & 0xFF;
-                *(outbuffer + offset++) = (data[i] >> (8 * 3)) & 0xFF;
-                *(outbuffer + offset++) = (data[i] > 0) ? 0: 255;
-                *(outbuffer + offset++) = (data[i] > 0) ? 0: 255;
-                *(outbuffer + offset++) = (data[i] > 0) ? 0: 255;
-                *(outbuffer + offset++) = (data[i] > 0) ? 0: 255;
-
-            }
-            return offset;
-        }
-
-        virtual int deserialize(unsigned char *inbuffer) {
-            int offset = 0;
-            offset += this->layout.deserialize(inbuffer + offset);
-            unsigned char data_lengthT = *(inbuffer + offset++);
-            if (data_lengthT > data_length)
-                this->data = (long*)realloc(this->data, data_lengthT * sizeof(long));
-            offset += 3;
-            data_length = data_lengthT;
-            for ( unsigned char i = 0; i < data_length; i++) {
-                st_data = 0;
-                st_data += ((long)(*(inbuffer + offset++))) >> (8 * 0);
-                st_data += ((long)(*(inbuffer + offset++))) >> (8 * 1);
-                st_data += ((long)(*(inbuffer + offset++))) >> (8 * 2);
-                st_data += ((long)(*(inbuffer + offset++))) >> (8 * 3);
-                offset += 4;
-                memcpy( &(this->data[i]), &(this->st_data), sizeof(long));
-            }
-            return offset;
-        }
-    */
-    virtual const char * getType() {
-        return "std_msgs/Int64MultiArray";
-    };
-
-};
-
-}
+#ifndef _ROS_std_msgs_Int64MultiArray_h
+#define _ROS_std_msgs_Int64MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs {
+
+class Int64MultiArray : public ros::Msg {
+public:
+    std_msgs::MultiArrayLayout layout;
+    unsigned char data_length;
+    int64_t st_data;
+    int64_t * data;
+
+    virtual int serialize(unsigned char *outbuffer) const {
+        int offset = 0;
+        offset += this->layout.serialize(outbuffer + offset);
+        *(outbuffer + offset++) = data_length;
+        *(outbuffer + offset++) = 0;
+        *(outbuffer + offset++) = 0;
+        *(outbuffer + offset++) = 0;
+        for ( unsigned char i = 0; i < data_length; i++) {
+            union {
+                int64_t real;
+                uint64_t base;
+            } u_datai;
+            u_datai.real = this->data[i];
+            *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+            *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF;
+            *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF;
+            *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF;
+            *(outbuffer + offset + 4) = (u_datai.base >> (8 * 4)) & 0xFF;
+            *(outbuffer + offset + 5) = (u_datai.base >> (8 * 5)) & 0xFF;
+            *(outbuffer + offset + 6) = (u_datai.base >> (8 * 6)) & 0xFF;
+            *(outbuffer + offset + 7) = (u_datai.base >> (8 * 7)) & 0xFF;
+            offset += sizeof(this->data[i]);
+        }
+        return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer) {
+        int offset = 0;
+        offset += this->layout.deserialize(inbuffer + offset);
+        unsigned char data_lengthT = *(inbuffer + offset++);
+        if (data_lengthT > data_length)
+            this->data = (int64_t*)realloc(this->data, data_lengthT * sizeof(int64_t));
+        offset += 3;
+        data_length = data_lengthT;
+        for ( unsigned char i = 0; i < data_length; i++) {
+            union {
+                int64_t real;
+                uint64_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 |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 4))) << (8 * 4);
+            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 5))) << (8 * 5);
+            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 6))) << (8 * 6);
+            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 7))) << (8 * 7);
+            this->st_data = u_st_data.real;
+            offset += sizeof(this->st_data);
+            memcpy( &(this->data[i]), &(this->st_data), sizeof(int64_t));
+        }
+        return offset;
+    }
+
+    virtual const char * getType() {
+        return "std_msgs/Int64MultiArray";
+    };
+    virtual const char * getMD5() {
+        return "54865aa6c65be0448113a2afc6a49270";
+    };
+
+};
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/Int8.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/Int8.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,49 +1,50 @@
-#ifndef ros_Int8_h
-#define ros_Int8_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-
-namespace std_msgs
-{
-
-  class Int8 : public ros::Msg
-  {
-    public:
-      int8_t data;
-
-    virtual int serialize(unsigned char *outbuffer)
-    {
-      int offset = 0;
-      union {
-        int8_t real;
-        uint8_t base;
-      } u_data;
-      u_data.real = this->data;
-      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
-      offset += sizeof(this->data);
-      return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer)
-    {
-      int offset = 0;
-      union {
-        int8_t real;
-        uint8_t base;
-      } u_data;
-      u_data.base = 0;
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      this->data = u_data.real;
-      offset += sizeof(this->data);
-     return offset;
-    }
-
-   virtual const char * getType(){ return "std_msgs/Int8"; };
-
-  };
-
-}
+#ifndef _ROS_std_msgs_Int8_h
+#define _ROS_std_msgs_Int8_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class Int8 : public ros::Msg
+  {
+    public:
+      int8_t data;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      union {
+        int8_t real;
+        uint8_t base;
+      } u_data;
+      u_data.real = this->data;
+      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        int8_t real;
+        uint8_t base;
+      } u_data;
+      u_data.base = 0;
+      u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->data = u_data.real;
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/Int8"; };
+    virtual const char * getMD5(){ return "27ffa0c9c4b8fb8492252bcad9e5c57b"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/Int8MultiArray.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/Int8MultiArray.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,69 +1,70 @@
-#ifndef ros_Int8MultiArray_h
-#define ros_Int8MultiArray_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-#include "std_msgs/MultiArrayLayout.h"
-
-namespace std_msgs
-{
-
-  class Int8MultiArray : public ros::Msg
-  {
-    public:
-      std_msgs::MultiArrayLayout layout;
-      unsigned char data_length;
-      int8_t st_data;
-      int8_t * data;
-
-    virtual int serialize(unsigned char *outbuffer)
-    {
-      int offset = 0;
-      offset += this->layout.serialize(outbuffer + offset);
-      *(outbuffer + offset++) = data_length;
-      *(outbuffer + offset++) = 0;
-      *(outbuffer + offset++) = 0;
-      *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < data_length; i++){
-      union {
-        int8_t real;
-        uint8_t base;
-      } u_datai;
-      u_datai.real = this->data[i];
-      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
-      offset += sizeof(this->data[i]);
-      }
-      return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer)
-    {
-      int offset = 0;
-      offset += this->layout.deserialize(inbuffer + offset);
-      unsigned char data_lengthT = *(inbuffer + offset++);
-      if(data_lengthT > data_length)
-        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++){
-      union {
-        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);
-      this->st_data = u_st_data.real;
-      offset += sizeof(this->st_data);
-        memcpy( &(this->data[i]), &(this->st_data), sizeof(int8_t));
-      }
-     return offset;
-    }
-
-   virtual const char * getType(){ return "std_msgs/Int8MultiArray"; };
-
-  };
-
-}
+#ifndef _ROS_std_msgs_Int8MultiArray_h
+#define _ROS_std_msgs_Int8MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class Int8MultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      uint8_t data_length;
+      int8_t st_data;
+      int8_t * data;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->layout.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        int8_t real;
+        uint8_t base;
+      } u_datai;
+      u_datai.real = this->data[i];
+      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      uint8_t data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t));
+      offset += 3;
+      data_length = data_lengthT;
+      for( uint8_t i = 0; i < data_length; i++){
+      union {
+        int8_t real;
+        uint8_t base;
+      } u_st_data;
+      u_st_data.base = 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(int8_t));
+      }
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/Int8MultiArray"; };
+    virtual const char * getMD5(){ return "d7c1af35a1b4781bbe79e03dd94b7c13"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/MultiArrayDimension.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/MultiArrayDimension.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,91 +1,70 @@
-#ifndef ros_MultiArrayDimension_h
-#define ros_MultiArrayDimension_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-
-namespace std_msgs
-{
-
-  class MultiArrayDimension : public ros::Msg
-  {
-    public:
-      char * label;
-      uint32_t size;
-      uint32_t stride;
-
-    virtual int serialize(unsigned char *outbuffer)
-    {
-      int offset = 0;
-      long * length_label = (long *)(outbuffer + offset);
-      *length_label = strlen( (const char*) this->label);
-      offset += 4;
-      memcpy(outbuffer + offset, this->label, *length_label);
-      offset += *length_label;
-      union {
-        uint32_t real;
-        uint32_t base;
-      } u_size;
-      u_size.real = this->size;
-      *(outbuffer + offset + 0) = (u_size.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_size.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_size.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_size.base >> (8 * 3)) & 0xFF;
-      offset += sizeof(this->size);
-      union {
-        uint32_t real;
-        uint32_t base;
-      } u_stride;
-      u_stride.real = this->stride;
-      *(outbuffer + offset + 0) = (u_stride.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_stride.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_stride.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_stride.base >> (8 * 3)) & 0xFF;
-      offset += sizeof(this->stride);
-      return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer)
-    {
-      int offset = 0;
-      uint32_t length_label = *(uint32_t *)(inbuffer + offset);
-      offset += 4;
-      for(unsigned int k= offset; k< offset+length_label; ++k){
-          inbuffer[k-1]=inbuffer[k];
-           }
-      inbuffer[offset+length_label-1]=0;
-      this->label = (char *)(inbuffer + offset-1);
-      offset += length_label;
-      union {
-        uint32_t real;
-        uint32_t base;
-      } u_size;
-      u_size.base = 0;
-      u_size.base |= ((typeof(u_size.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_size.base |= ((typeof(u_size.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_size.base |= ((typeof(u_size.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_size.base |= ((typeof(u_size.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->size = u_size.real;
-      offset += sizeof(this->size);
-      union {
-        uint32_t real;
-        uint32_t base;
-      } u_stride;
-      u_stride.base = 0;
-      u_stride.base |= ((typeof(u_stride.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_stride.base |= ((typeof(u_stride.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_stride.base |= ((typeof(u_stride.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_stride.base |= ((typeof(u_stride.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->stride = u_stride.real;
-      offset += sizeof(this->stride);
-     return offset;
-    }
-
-   virtual const char * getType(){ return "std_msgs/MultiArrayDimension"; };
-
-  };
-
-}
+#ifndef _ROS_std_msgs_MultiArrayDimension_h
+#define _ROS_std_msgs_MultiArrayDimension_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class MultiArrayDimension : public ros::Msg
+  {
+    public:
+      char * label;
+      uint32_t size;
+      uint32_t stride;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t * length_label = (uint32_t *)(outbuffer + offset);
+      *length_label = strlen( (const char*) this->label);
+      offset += 4;
+      memcpy(outbuffer + offset, this->label, *length_label);
+      offset += *length_label;
+      *(outbuffer + offset + 0) = (this->size >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->size >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->size >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->size >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->size);
+      *(outbuffer + offset + 0) = (this->stride >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->stride >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->stride >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->stride >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->stride);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_label = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_label; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_label-1]=0;
+      this->label = (char *)(inbuffer + offset-1);
+      offset += length_label;
+      this->size |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->size |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->size |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->size |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->size);
+      this->stride |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->stride |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->stride |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->stride |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->stride);
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/MultiArrayDimension"; };
+    virtual const char * getMD5(){ return "4cd0c83a8683deae40ecdac60e53bfa8"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/MultiArrayLayout.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/MultiArrayLayout.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,73 +1,65 @@
-#ifndef ros_MultiArrayLayout_h
-#define ros_MultiArrayLayout_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-#include "std_msgs/MultiArrayDimension.h"
-
-namespace std_msgs {
-
-class MultiArrayLayout : public ros::Msg {
-public:
-    unsigned char dim_length;
-    std_msgs::MultiArrayDimension st_dim;
-    std_msgs::MultiArrayDimension * dim;
-    unsigned long data_offset;
-
-    virtual int serialize(unsigned char *outbuffer) {
-        int offset = 0;
-        *(outbuffer + offset++) = dim_length;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        for ( unsigned char i = 0; i < dim_length; i++) {
-            offset += this->dim[i].serialize(outbuffer + offset);
-        }
-        union {
-            uint32_t real;
-            uint32_t base;
-        } u_data_offset;
-        u_data_offset.real = this->data_offset;
-        *(outbuffer + offset + 0) = (u_data_offset.base >> (8 * 0)) & 0xFF;
-        *(outbuffer + offset + 1) = (u_data_offset.base >> (8 * 1)) & 0xFF;
-        *(outbuffer + offset + 2) = (u_data_offset.base >> (8 * 2)) & 0xFF;
-        *(outbuffer + offset + 3) = (u_data_offset.base >> (8 * 3)) & 0xFF;
-        offset += sizeof(this->data_offset);
-        return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer) {
-        int offset = 0;
-        unsigned char dim_lengthT = *(inbuffer + offset++);
-        if (dim_lengthT > dim_length)
-            this->dim = (std_msgs::MultiArrayDimension*)realloc(this->dim, dim_lengthT * sizeof(std_msgs::MultiArrayDimension));
-        offset += 3;
-        dim_length = dim_lengthT;
-        for ( unsigned char i = 0; i < dim_length; i++) {
-            offset += this->st_dim.deserialize(inbuffer + offset);
-            memcpy( &(this->dim[i]), &(this->st_dim), sizeof(std_msgs::MultiArrayDimension));
-        }
-        union {
-            uint32_t real;
-            uint32_t base;
-        } u_data_offset;
-        u_data_offset.base = 0;
-        u_data_offset.base |= ((typeof(u_data_offset.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-        u_data_offset.base |= ((typeof(u_data_offset.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-        u_data_offset.base |= ((typeof(u_data_offset.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-        u_data_offset.base |= ((typeof(u_data_offset.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-        this->data_offset = u_data_offset.real;
-        offset += sizeof(this->data_offset);
-        return offset;
-    }
-
-    virtual const char * getType() {
-        return "std_msgs/MultiArrayLayout";
-    };
-
-};
-
-}
+#ifndef _ROS_std_msgs_MultiArrayLayout_h
+#define _ROS_std_msgs_MultiArrayLayout_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/MultiArrayDimension.h"
+
+namespace std_msgs
+{
+
+  class MultiArrayLayout : public ros::Msg
+  {
+    public:
+      uint8_t dim_length;
+      std_msgs::MultiArrayDimension st_dim;
+      std_msgs::MultiArrayDimension * dim;
+      uint32_t data_offset;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = dim_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < dim_length; i++){
+      offset += this->dim[i].serialize(outbuffer + offset);
+      }
+      *(outbuffer + offset + 0) = (this->data_offset >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data_offset >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data_offset >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data_offset >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data_offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t dim_lengthT = *(inbuffer + offset++);
+      if(dim_lengthT > dim_length)
+        this->dim = (std_msgs::MultiArrayDimension*)realloc(this->dim, dim_lengthT * sizeof(std_msgs::MultiArrayDimension));
+      offset += 3;
+      dim_length = dim_lengthT;
+      for( uint8_t i = 0; i < dim_length; i++){
+      offset += this->st_dim.deserialize(inbuffer + offset);
+        memcpy( &(this->dim[i]), &(this->st_dim), sizeof(std_msgs::MultiArrayDimension));
+      }
+      this->data_offset |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->data_offset |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->data_offset |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->data_offset |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->data_offset);
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/MultiArrayLayout"; };
+    virtual const char * getMD5(){ return "0fed2a11c13e11c5571b4e2a995a91a3"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/String.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/String.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,49 +1,48 @@
-#ifndef ros_String_h
-#define ros_String_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-#include"mbed.h"
-
-
-namespace std_msgs
-{
-
-  class String : public ros::Msg
-  {
-    public:
-      char * data;
-
-    virtual int serialize(unsigned char *outbuffer)
-    {
-      int offset = 0;
-      long * length_data = (long *)(outbuffer + offset);
-      *length_data = strlen( (const char*) this->data);
-      offset += 4;
-      memcpy(outbuffer + offset, this->data, *length_data);
-      offset += *length_data;
-      return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer)
-    {
-      int offset = 0;
-      uint32_t length_data = *(uint32_t *)(inbuffer + offset);
-      offset += 4;
-      for(unsigned int k= offset; k< offset+length_data; ++k){
-          inbuffer[k-1]=inbuffer[k];
-           }
-      inbuffer[offset+length_data-1]=0;
-      this->data = (char *)(inbuffer + offset-1);
-      offset += length_data;
-     return offset;
-    }
-
-    virtual const char * getType(){ return "std_msgs/String"; };
-
-  };
-
-}
+#ifndef _ROS_std_msgs_String_h
+#define _ROS_std_msgs_String_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class String : public ros::Msg
+  {
+    public:
+      char * data;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t * length_data = (uint32_t *)(outbuffer + offset);
+      *length_data = strlen( (const char*) this->data);
+      offset += 4;
+      memcpy(outbuffer + offset, this->data, *length_data);
+      offset += *length_data;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_data = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_data; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_data-1]=0;
+      this->data = (char *)(inbuffer + offset-1);
+      offset += length_data;
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/String"; };
+    virtual const char * getMD5(){ return "992ce8a1687cec8c8bd883ec73ca41d1"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/Time.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/Time.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,77 +1,56 @@
-#ifndef ros_std_msgs_Time_h
-#define ros_std_msgs_Time_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-#include "ros/time.h"
-
-namespace std_msgs
-{
-
-  class Time : public ros::Msg
-  {
-    public:
-      ros::Time data;
-
-    virtual int serialize(unsigned char *outbuffer)
-    {
-      int offset = 0;
-      union {
-        uint32_t real;
-        uint32_t base;
-      } u_sec;
-      u_sec.real = this->data.sec;
-      *(outbuffer + offset + 0) = (u_sec.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_sec.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_sec.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_sec.base >> (8 * 3)) & 0xFF;
-      offset += sizeof(this->data.sec);
-      union {
-        uint32_t real;
-        uint32_t base;
-      } u_nsec;
-      u_nsec.real = this->data.nsec;
-      *(outbuffer + offset + 0) = (u_nsec.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_nsec.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_nsec.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_nsec.base >> (8 * 3)) & 0xFF;
-      offset += sizeof(this->data.nsec);
-      return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer)
-    {
-      int offset = 0;
-      union {
-        uint32_t real;
-        uint32_t base;
-      } u_sec;
-      u_sec.base = 0;
-      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->data.sec = u_sec.real;
-      offset += sizeof(this->data.sec);
-      union {
-        uint32_t real;
-        uint32_t base;
-      } u_nsec;
-      u_nsec.base = 0;
-      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->data.nsec = u_nsec.real;
-      offset += sizeof(this->data.nsec);
-     return offset;
-    }
-
-    virtual const char * getType(){ return "std_msgs/Time"; };
-
-  };
-
-}
+#ifndef _ROS_std_msgs_Time_h
+#define _ROS_std_msgs_Time_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "ros/time.h"
+
+namespace std_msgs
+{
+
+  class Time : public ros::Msg
+  {
+    public:
+      ros::Time data;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->data.sec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data.sec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data.sec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data.sec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data.sec);
+      *(outbuffer + offset + 0) = (this->data.nsec >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data.nsec >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data.nsec >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data.nsec >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data.nsec);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->data.sec |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->data.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->data.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->data.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->data.sec);
+      this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->data.nsec);
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/Time"; };
+    virtual const char * getMD5(){ return "cd7166c74c552c311fbcc2fe5a7bc289"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/UInt16.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/UInt16.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,51 +1,41 @@
-#ifndef ros_UInt16_h
-#define ros_UInt16_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-
-namespace std_msgs
-{
-
-  class UInt16 : public ros::Msg
-  {
-    public:
-      uint16_t data;
-
-    virtual int serialize(unsigned char *outbuffer)
-    {
-      int offset = 0;
-      union {
-        uint16_t real;
-        uint16_t base;
-      } u_data;
-      u_data.real = this->data;
-      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF;
-      offset += sizeof(this->data);
-      return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer)
-    {
-      int offset = 0;
-      union {
-        uint16_t real;
-        uint16_t base;
-      } u_data;
-      u_data.base = 0;
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      this->data = u_data.real;
-      offset += sizeof(this->data);
-     return offset;
-    }
-
-    virtual const char * getType(){ return "std_msgs/UInt16"; };
-
-  };
-
-}
+#ifndef _ROS_std_msgs_UInt16_h
+#define _ROS_std_msgs_UInt16_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class UInt16 : public ros::Msg
+  {
+    public:
+      uint16_t data;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->data |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->data |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/UInt16"; };
+    virtual const char * getMD5(){ return "1df79edf208b629fe6b81923a544552d"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/UInt16MultiArray.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/UInt16MultiArray.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,71 +1,61 @@
-#ifndef ros_UInt16MultiArray_h
-#define ros_UInt16MultiArray_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-#include "std_msgs/MultiArrayLayout.h"
-
-namespace std_msgs
-{
-
-  class UInt16MultiArray : public ros::Msg
-  {
-    public:
-      std_msgs::MultiArrayLayout layout;
-      unsigned char data_length;
-      uint16_t st_data;
-      uint16_t * data;
-
-    virtual int serialize(unsigned char *outbuffer)
-    {
-      int offset = 0;
-      offset += this->layout.serialize(outbuffer + offset);
-      *(outbuffer + offset++) = data_length;
-      *(outbuffer + offset++) = 0;
-      *(outbuffer + offset++) = 0;
-      *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < data_length; i++){
-      union {
-        uint16_t real;
-        uint16_t base;
-      } u_datai;
-      u_datai.real = this->data[i];
-      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF;
-      offset += sizeof(this->data[i]);
-      }
-      return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer)
-    {
-      int offset = 0;
-      offset += this->layout.deserialize(inbuffer + offset);
-      unsigned char data_lengthT = *(inbuffer + offset++);
-      if(data_lengthT > data_length)
-        this->data = (uint16_t*)realloc(this->data, data_lengthT * sizeof(uint16_t));
-      offset += 3;
-      data_length = data_lengthT;
-      for( unsigned char i = 0; i < data_length; i++){
-      union {
-        uint16_t real;
-        uint16_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 |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      this->st_data = u_st_data.real;
-      offset += sizeof(this->st_data);
-        memcpy( &(this->data[i]), &(this->st_data), sizeof(uint16_t));
-      }
-     return offset;
-    }
-
-   virtual const char * getType(){ return "std_msgs/UInt16MultiArray"; };
-
-  };
-
-}
+#ifndef _ROS_std_msgs_UInt16MultiArray_h
+#define _ROS_std_msgs_UInt16MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class UInt16MultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      uint8_t data_length;
+      uint16_t st_data;
+      uint16_t * data;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->layout.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < data_length; i++){
+      *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data[i] >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      uint8_t data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (uint16_t*)realloc(this->data, data_lengthT * sizeof(uint16_t));
+      offset += 3;
+      data_length = data_lengthT;
+      for( uint8_t i = 0; i < data_length; i++){
+      this->st_data |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->st_data |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(uint16_t));
+      }
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/UInt16MultiArray"; };
+    virtual const char * getMD5(){ return "52f264f1c973c4b73790d384c6cb4484"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/UInt32.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/UInt32.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,55 +1,45 @@
-#ifndef ros_UInt32_h
-#define ros_UInt32_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-
-namespace std_msgs
-{
-
-  class UInt32 : public ros::Msg
-  {
-    public:
-      uint32_t data;
-
-    virtual int serialize(unsigned char *outbuffer)
-    {
-      int offset = 0;
-      union {
-        uint32_t real;
-        uint32_t base;
-      } u_data;
-      u_data.real = this->data;
-      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF;
-      offset += sizeof(this->data);
-      return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer)
-    {
-      int offset = 0;
-      union {
-        uint32_t real;
-        uint32_t base;
-      } u_data;
-      u_data.base = 0;
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->data = u_data.real;
-      offset += sizeof(this->data);
-     return offset;
-    }
-
-   virtual const char * getType(){ return "std_msgs/UInt32"; };
-
-  };
-
-}
+#ifndef _ROS_std_msgs_UInt32_h
+#define _ROS_std_msgs_UInt32_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class UInt32 : public ros::Msg
+  {
+    public:
+      uint32_t data;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->data |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->data |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->data |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->data |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/UInt32"; };
+    virtual const char * getMD5(){ return "304a39449588c7f8ce2df6e8001c5fce"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/UInt32MultiArray.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/UInt32MultiArray.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,75 +1,65 @@
-#ifndef ros_UInt32MultiArray_h
-#define ros_UInt32MultiArray_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-#include "std_msgs/MultiArrayLayout.h"
-
-namespace std_msgs
-{
-
-  class UInt32MultiArray : public ros::Msg
-  {
-    public:
-      std_msgs::MultiArrayLayout layout;
-      unsigned char data_length;
-      uint32_t st_data;
-      uint32_t * data;
-
-    virtual int serialize(unsigned char *outbuffer)
-    {
-      int offset = 0;
-      offset += this->layout.serialize(outbuffer + offset);
-      *(outbuffer + offset++) = data_length;
-      *(outbuffer + offset++) = 0;
-      *(outbuffer + offset++) = 0;
-      *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < data_length; i++){
-      union {
-        uint32_t real;
-        uint32_t base;
-      } u_datai;
-      u_datai.real = this->data[i];
-      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
-      *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF;
-      *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF;
-      *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF;
-      offset += sizeof(this->data[i]);
-      }
-      return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer)
-    {
-      int offset = 0;
-      offset += this->layout.deserialize(inbuffer + offset);
-      unsigned char data_lengthT = *(inbuffer + offset++);
-      if(data_lengthT > data_length)
-        this->data = (uint32_t*)realloc(this->data, data_lengthT * sizeof(uint32_t));
-      offset += 3;
-      data_length = data_lengthT;
-      for( unsigned char i = 0; i < data_length; i++){
-      union {
-        uint32_t real;
-        uint32_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 |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-      u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-      u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-      this->st_data = u_st_data.real;
-      offset += sizeof(this->st_data);
-        memcpy( &(this->data[i]), &(this->st_data), sizeof(uint32_t));
-      }
-     return offset;
-    }
-
-   virtual const char * getType(){ return "std_msgs/UInt32MultiArray"; };
-
-  };
-
-}
+#ifndef _ROS_std_msgs_UInt32MultiArray_h
+#define _ROS_std_msgs_UInt32MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class UInt32MultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      uint8_t data_length;
+      uint32_t st_data;
+      uint32_t * data;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->layout.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < data_length; i++){
+      *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->data[i] >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (this->data[i] >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (this->data[i] >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      uint8_t data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (uint32_t*)realloc(this->data, data_lengthT * sizeof(uint32_t));
+      offset += 3;
+      data_length = data_lengthT;
+      for( uint8_t i = 0; i < data_length; i++){
+      this->st_data |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->st_data |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->st_data |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
+      this->st_data |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(uint32_t));
+      }
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/UInt32MultiArray"; };
+    virtual const char * getMD5(){ return "4d6a180abc9be191b96a7eda6c8a233d"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/UInt64.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/UInt64.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,91 +1,64 @@
-#ifndef ros_UInt64_h
-#define ros_UInt64_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-
-namespace std_msgs {
-
-class UInt64 : public ros::Msg {
-public:
-    uint64_t data;
-
-    virtual int serialize(unsigned char *outbuffer) {
-        int offset = 0;
-        union {
-            uint64_t real;
-            uint64_t base;
-        } u_data;
-        u_data.real = this->data;
-        *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
-        *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF;
-        *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF;
-        *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF;
-        *(outbuffer + offset + 4) = (u_data.base >> (8 * 4)) & 0xFF;
-        *(outbuffer + offset + 5) = (u_data.base >> (8 * 5)) & 0xFF;
-        *(outbuffer + offset + 6) = (u_data.base >> (8 * 6)) & 0xFF;
-        *(outbuffer + offset + 7) = (u_data.base >> (8 * 7)) & 0xFF;
-        offset += sizeof(this->data);
-        return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer) {
-        int offset = 0;
-        union {
-            uint64_t real;
-            uint64_t base;
-        } u_data;
-        u_data.base = 0;
-        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 4))) << (8 * 4);
-        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 5))) << (8 * 5);
-        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 6))) << (8 * 6);
-        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 7))) << (8 * 7);
-        this->data = u_data.real;
-        offset += sizeof(this->data);
-        return offset;
-    }
-
-    /*
-      public:
-        long data;
-
-      virtual int serialize(unsigned char *outbuffer)
-      {
-        int offset = 0;
-        *(outbuffer + offset++) = (data >> (8 * 0)) & 0xFF;
-        *(outbuffer + offset++) = (data >> (8 * 1)) & 0xFF;
-        *(outbuffer + offset++) = (data >> (8 * 2)) & 0xFF;
-        *(outbuffer + offset++) = (data >> (8 * 3)) & 0xFF;
-        *(outbuffer + offset++) = (data > 0) ? 0: 255;
-        *(outbuffer + offset++) = (data > 0) ? 0: 255;
-        *(outbuffer + offset++) = (data > 0) ? 0: 255;
-        *(outbuffer + offset++) = (data > 0) ? 0: 255;
-        return offset;
-      }
-
-      virtual int deserialize(unsigned char *inbuffer)
-      {
-        int offset = 0;
-        data = 0;
-        data += ((long)(*(inbuffer + offset++))) >> (8 * 0);
-        data += ((long)(*(inbuffer + offset++))) >> (8 * 1);
-        data += ((long)(*(inbuffer + offset++))) >> (8 * 2);
-        data += ((long)(*(inbuffer + offset++))) >> (8 * 3);
-        offset += 4;
-       return offset;
-      }
-    */
-    virtual const char * getType() {
-        return "std_msgs/UInt64";
-    };
-
-};
-
-}
+#ifndef _ROS_std_msgs_UInt64_h
+#define _ROS_std_msgs_UInt64_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs {
+
+class UInt64 : public ros::Msg {
+public:
+    uint64_t data;
+
+    virtual int serialize(unsigned char *outbuffer) const {
+        int offset = 0;
+        union {
+            uint64_t real;
+            uint64_t base;
+        } u_data;
+        u_data.real = this->data;
+        *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+        *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF;
+        *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF;
+        *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF;
+        *(outbuffer + offset + 4) = (u_data.base >> (8 * 4)) & 0xFF;
+        *(outbuffer + offset + 5) = (u_data.base >> (8 * 5)) & 0xFF;
+        *(outbuffer + offset + 6) = (u_data.base >> (8 * 6)) & 0xFF;
+        *(outbuffer + offset + 7) = (u_data.base >> (8 * 7)) & 0xFF;
+        offset += sizeof(this->data);
+        return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer) {
+        int offset = 0;
+        union {
+            uint64_t real;
+            uint64_t base;
+        } u_data;
+        u_data.base = 0;
+        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 4))) << (8 * 4);
+        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 5))) << (8 * 5);
+        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 6))) << (8 * 6);
+        u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 7))) << (8 * 7);
+        this->data = u_data.real;
+        offset += sizeof(this->data);
+        return offset;
+    }
+
+    virtual const char * getType() {
+        return "std_msgs/UInt64";
+    };
+    virtual const char * getMD5() {
+        return "1b2a79973e8bf53d7b53acb71299cb57";
+    };
+
+};
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/UInt64MultiArray.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/UInt64MultiArray.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,129 +1,82 @@
-#ifndef ros_UInt64MultiArray_h
-#define ros_UInt64MultiArray_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-#include "std_msgs/MultiArrayLayout.h"
-
-namespace std_msgs {
-
-class UInt64MultiArray : public ros::Msg {
-public:
-    std_msgs::MultiArrayLayout layout;
-    unsigned char data_length;
-    uint64_t st_data;
-    uint64_t * data;
-
-    virtual int serialize(unsigned char *outbuffer) {
-        int offset = 0;
-        offset += this->layout.serialize(outbuffer + offset);
-        *(outbuffer + offset++) = data_length;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        for ( unsigned char i = 0; i < data_length; i++) {
-            union {
-                uint64_t real;
-                uint64_t base;
-            } u_datai;
-            u_datai.real = this->data[i];
-            *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
-            *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF;
-            *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF;
-            *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF;
-            *(outbuffer + offset + 4) = (u_datai.base >> (8 * 4)) & 0xFF;
-            *(outbuffer + offset + 5) = (u_datai.base >> (8 * 5)) & 0xFF;
-            *(outbuffer + offset + 6) = (u_datai.base >> (8 * 6)) & 0xFF;
-            *(outbuffer + offset + 7) = (u_datai.base >> (8 * 7)) & 0xFF;
-            offset += sizeof(this->data[i]);
-        }
-        return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer) {
-        int offset = 0;
-        offset += this->layout.deserialize(inbuffer + offset);
-        unsigned char data_lengthT = *(inbuffer + offset++);
-        if (data_lengthT > data_length)
-            this->data = (uint64_t*)realloc(this->data, data_lengthT * sizeof(uint64_t));
-        offset += 3;
-        data_length = data_lengthT;
-        for ( unsigned char i = 0; i < data_length; i++) {
-            union {
-                uint64_t real;
-                uint64_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 |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 1))) << (8 * 1);
-            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 2))) << (8 * 2);
-            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 3))) << (8 * 3);
-            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 4))) << (8 * 4);
-            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 5))) << (8 * 5);
-            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 6))) << (8 * 6);
-            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 7))) << (8 * 7);
-            this->st_data = u_st_data.real;
-            offset += sizeof(this->st_data);
-            memcpy( &(this->data[i]), &(this->st_data), sizeof(uint64_t));
-        }
-        return offset;
-    }
-    /*
-      public:
-        std_msgs::MultiArrayLayout layout;
-        unsigned char data_length;
-        long st_data;
-        long * data;
-
-      virtual int serialize(unsigned char *outbuffer)
-      {
-        int offset = 0;
-        offset += this->layout.serialize(outbuffer + offset);
-        *(outbuffer + offset++) = data_length;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        *(outbuffer + offset++) = 0;
-        for( unsigned char i = 0; i < data_length; i++){
-        *(outbuffer + offset++) = (data[i] >> (8 * 0)) & 0xFF;
-        *(outbuffer + offset++) = (data[i] >> (8 * 1)) & 0xFF;
-        *(outbuffer + offset++) = (data[i] >> (8 * 2)) & 0xFF;
-        *(outbuffer + offset++) = (data[i] >> (8 * 3)) & 0xFF;
-        *(outbuffer + offset++) = (data[i] > 0) ? 0: 255;
-        *(outbuffer + offset++) = (data[i] > 0) ? 0: 255;
-        *(outbuffer + offset++) = (data[i] > 0) ? 0: 255;
-        *(outbuffer + offset++) = (data[i] > 0) ? 0: 255;
-        }
-        return offset;
-      }
-
-      virtual int deserialize(unsigned char *inbuffer)
-      {
-        int offset = 0;
-        offset += this->layout.deserialize(inbuffer + offset);
-        unsigned char data_lengthT = *(inbuffer + offset++);
-        if(data_lengthT > data_length)
-          this->data = (long*)realloc(this->data, data_lengthT * sizeof(long));
-        offset += 3;
-        data_length = data_lengthT;
-        for( unsigned char i = 0; i < data_length; i++){
-        st_data = 0;
-        st_data += ((long)(*(inbuffer + offset++))) >> (8 * 0);
-        st_data += ((long)(*(inbuffer + offset++))) >> (8 * 1);
-        st_data += ((long)(*(inbuffer + offset++))) >> (8 * 2);
-        st_data += ((long)(*(inbuffer + offset++))) >> (8 * 3);
-        offset += 4;
-          memcpy( &(this->data[i]), &(this->st_data), sizeof(long));
-        }
-       return offset;
-      }
-    */
-    virtual const char * getType() {
-        return "std_msgs/UInt64MultiArray";
-    };
-
-};
-
-}
+#ifndef _ROS_std_msgs_UInt64MultiArray_h
+#define _ROS_std_msgs_UInt64MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class UInt64MultiArray : public ros::Msg
+  {
+public:
+    std_msgs::MultiArrayLayout layout;
+    unsigned char data_length;
+    uint64_t st_data;
+    uint64_t * data;
+
+    virtual int serialize(unsigned char *outbuffer) const {
+        int offset = 0;
+        offset += this->layout.serialize(outbuffer + offset);
+        *(outbuffer + offset++) = data_length;
+        *(outbuffer + offset++) = 0;
+        *(outbuffer + offset++) = 0;
+        *(outbuffer + offset++) = 0;
+        for ( unsigned char i = 0; i < data_length; i++) {
+            union {
+                uint64_t real;
+                uint64_t base;
+            } u_datai;
+            u_datai.real = this->data[i];
+            *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+            *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF;
+            *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF;
+            *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF;
+            *(outbuffer + offset + 4) = (u_datai.base >> (8 * 4)) & 0xFF;
+            *(outbuffer + offset + 5) = (u_datai.base >> (8 * 5)) & 0xFF;
+            *(outbuffer + offset + 6) = (u_datai.base >> (8 * 6)) & 0xFF;
+            *(outbuffer + offset + 7) = (u_datai.base >> (8 * 7)) & 0xFF;
+            offset += sizeof(this->data[i]);
+        }
+        return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer) {
+        int offset = 0;
+        offset += this->layout.deserialize(inbuffer + offset);
+        unsigned char data_lengthT = *(inbuffer + offset++);
+        if (data_lengthT > data_length)
+            this->data = (uint64_t*)realloc(this->data, data_lengthT * sizeof(uint64_t));
+        offset += 3;
+        data_length = data_lengthT;
+        for ( unsigned char i = 0; i < data_length; i++) {
+            union {
+                uint64_t real;
+                uint64_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 |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 4))) << (8 * 4);
+            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 5))) << (8 * 5);
+            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 6))) << (8 * 6);
+            u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 7))) << (8 * 7);
+            this->st_data = u_st_data.real;
+            offset += sizeof(this->st_data);
+            memcpy( &(this->data[i]), &(this->st_data), sizeof(uint64_t));
+        }
+        return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/UInt64MultiArray"; };
+    virtual const char * getMD5(){ return "6088f127afb1d6c72927aa1247e945af"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/UInt8.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/UInt8.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,49 +1,39 @@
-#ifndef ros_UInt8_h
-#define ros_UInt8_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-
-namespace std_msgs
-{
-
-  class UInt8 : public ros::Msg
-  {
-    public:
-      uint8_t data;
-
-    virtual int serialize(unsigned char *outbuffer)
-    {
-      int offset = 0;
-      union {
-        uint8_t real;
-        uint8_t base;
-      } u_data;
-      u_data.real = this->data;
-      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
-      offset += sizeof(this->data);
-      return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer)
-    {
-      int offset = 0;
-      union {
-        uint8_t real;
-        uint8_t base;
-      } u_data;
-      u_data.base = 0;
-      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      this->data = u_data.real;
-      offset += sizeof(this->data);
-     return offset;
-    }
-
-   virtual const char * getType(){ return "std_msgs/UInt8"; };
-
-  };
-
-}
+#ifndef _ROS_std_msgs_UInt8_h
+#define _ROS_std_msgs_UInt8_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace std_msgs
+{
+
+  class UInt8 : public ros::Msg
+  {
+    public:
+      uint8_t data;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->data |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/UInt8"; };
+    virtual const char * getMD5(){ return "7c8164229e7d2c17eb95e9231617fdee"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- a/std_msgs/UInt8MultiArray.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/std_msgs/UInt8MultiArray.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,69 +1,59 @@
-#ifndef ros_UInt8MultiArray_h
-#define ros_UInt8MultiArray_h
-
-#include <stdint.h>
-#include <string.h>
-#include <stdlib.h>
-#include "../ros/msg.h"
-#include "std_msgs/MultiArrayLayout.h"
-
-namespace std_msgs
-{
-
-  class UInt8MultiArray : public ros::Msg
-  {
-    public:
-      std_msgs::MultiArrayLayout layout;
-      unsigned char data_length;
-      uint8_t st_data;
-      uint8_t * data;
-
-    virtual int serialize(unsigned char *outbuffer)
-    {
-      int offset = 0;
-      offset += this->layout.serialize(outbuffer + offset);
-      *(outbuffer + offset++) = data_length;
-      *(outbuffer + offset++) = 0;
-      *(outbuffer + offset++) = 0;
-      *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < data_length; i++){
-      union {
-        uint8_t real;
-        uint8_t base;
-      } u_datai;
-      u_datai.real = this->data[i];
-      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
-      offset += sizeof(this->data[i]);
-      }
-      return offset;
-    }
-
-    virtual int deserialize(unsigned char *inbuffer)
-    {
-      int offset = 0;
-      offset += this->layout.deserialize(inbuffer + offset);
-      unsigned char data_lengthT = *(inbuffer + offset++);
-      if(data_lengthT > data_length)
-        this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t));
-      offset += 3;
-      data_length = data_lengthT;
-      for( unsigned char i = 0; i < data_length; i++){
-      union {
-        uint8_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);
-      this->st_data = u_st_data.real;
-      offset += sizeof(this->st_data);
-        memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t));
-      }
-     return offset;
-    }
-
-   virtual const char * getType(){ return "std_msgs/UInt8MultiArray"; };
-
-  };
-
-}
+#ifndef _ROS_std_msgs_UInt8MultiArray_h
+#define _ROS_std_msgs_UInt8MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class UInt8MultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      uint8_t data_length;
+      uint8_t st_data;
+      uint8_t * data;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      offset += this->layout.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < data_length; i++){
+      *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      uint8_t data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t));
+      offset += 3;
+      data_length = data_lengthT;
+      for( uint8_t i = 0; i < data_length; i++){
+      this->st_data |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t));
+      }
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/UInt8MultiArray"; };
+    virtual const char * getMD5(){ return "82373f1612381bb6ee473b5cd6f5d89c"; };
+
+  };
+
+}
 #endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tests/array_test.cpp	Sat Nov 12 23:54:45 2011 +0000
@@ -0,0 +1,47 @@
+//#define COMPILE_ARRAY_CODE_RSOSSERIAL
+#ifdef COMPILE_ARRAY_CODE_RSOSSERIAL
+
+/*
+ * rosserial::geometry_msgs::PoseArray Test
+ * Sums an array, publishes sum
+ */
+#include "mbed.h"
+#include <ros.h>
+#include <geometry_msgs/Pose.h>
+#include <geometry_msgs/PoseArray.h>
+
+
+ros::NodeHandle nh;
+
+bool set_;
+DigitalOut myled(LED1);
+
+geometry_msgs::Pose sum_msg;
+ros::Publisher p("sum", &sum_msg);
+
+void messageCb(const geometry_msgs::PoseArray& msg) {
+    sum_msg.position.x = 0;
+    sum_msg.position.y = 0;
+    sum_msg.position.z = 0;
+    for (int i = 0; i < msg.poses_length; i++) {
+        sum_msg.position.x += msg.poses[i].position.x;
+        sum_msg.position.y += msg.poses[i].position.y;
+        sum_msg.position.z += msg.poses[i].position.z;
+    }
+    myled = !myled;   // blink the led
+}
+
+ros::Subscriber<geometry_msgs::PoseArray> s("poses",messageCb);
+
+int main() {
+    nh.initNode();
+    nh.subscribe(s);
+    nh.advertise(p);
+
+    while (1) {
+        p.publish(&sum_msg);
+        nh.spinOnce();
+        wait_ms(10);
+    }
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tests/float64_test.cpp	Sat Nov 12 23:54:45 2011 +0000
@@ -0,0 +1,39 @@
+//#define COMPLIE_FLOAT64_CODE_ROSSERIAL
+#ifdef  COMPILE_FLOAT64_CODE_ROSSERIAL
+
+/*
+ * rosserial::std_msgs::Float64 Test
+ * Receives a Float64 input, subtracts 1.0, and publishes it
+ */
+
+#include "mbed.h"
+#include <ros.h>
+#include <std_msgs/Float64.h>
+
+
+ros::NodeHandle nh;
+
+float x;
+DigitalOut myled(LED1);
+
+void messageCb( const std_msgs::Float64& msg) {
+    x = msg.data - 1.0;
+    myled = !myled; // blink the led
+}
+
+std_msgs::Float64 test;
+ros::Subscriber<std_msgs::Float64> s("your_topic", &messageCb);
+ros::Publisher p("my_topic", &test);
+
+int main() {
+    nh.initNode();
+    nh.advertise(p);
+    nh.subscribe(s);
+    while (1) {
+        test.data = x;
+        p.publish( &test );
+        nh.spinOnce();
+        wait_ms(10);
+    }
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tests/time_test.cpp	Sat Nov 12 23:54:45 2011 +0000
@@ -0,0 +1,31 @@
+//#define COMPILE_TIME_CODE_ROSSERIAL
+#ifdef COMPILE_TIME_CODE_ROSSERIAL
+
+/*
+ * rosserial::std_msgs::Time Test
+ * Publishes current time
+ */
+
+#include "mbed.h"
+#include <ros.h>
+#include <ros/time.h>
+#include <std_msgs/Time.h>
+
+
+ros::NodeHandle  nh;
+
+std_msgs::Time test;
+ros::Publisher p("my_topic", &test);
+
+int main() {
+    nh.initNode();
+    nh.advertise(p);
+
+    while (1) {
+        test.data = nh.now();
+        p.publish( &test );
+        nh.spinOnce();
+        wait_ms(10);
+    }
+}
+#endif
\ No newline at end of file
--- a/tf/FrameGraph.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/tf/FrameGraph.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,9 +1,9 @@
-#ifndef ros_SERVICE_FrameGraph_h
-#define ros_SERVICE_FrameGraph_h
+#ifndef _ROS_SERVICE_FrameGraph_h
+#define _ROS_SERVICE_FrameGraph_h
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 
 namespace tf
 {
@@ -14,7 +14,7 @@
   {
     public:
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       return offset;
@@ -26,7 +26,8 @@
      return offset;
     }
 
-    const char * getType(){ return FRAMEGRAPH; };
+    virtual const char * getType(){ return FRAMEGRAPH; };
+    virtual const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
 
   };
 
@@ -35,10 +36,10 @@
     public:
       char * dot_graph;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
-      long * length_dot_graph = (long *)(outbuffer + offset);
+      uint32_t * length_dot_graph = (uint32_t *)(outbuffer + offset);
       *length_dot_graph = strlen( (const char*) this->dot_graph);
       offset += 4;
       memcpy(outbuffer + offset, this->dot_graph, *length_dot_graph);
@@ -53,15 +54,22 @@
       offset += 4;
       for(unsigned int k= offset; k< offset+length_dot_graph; ++k){
           inbuffer[k-1]=inbuffer[k];
-           }
+      }
       inbuffer[offset+length_dot_graph-1]=0;
       this->dot_graph = (char *)(inbuffer + offset-1);
       offset += length_dot_graph;
      return offset;
     }
 
-    const char * getType(){ return FRAMEGRAPH; };
+    virtual const char * getType(){ return FRAMEGRAPH; };
+    virtual const char * getMD5(){ return "c4af9ac907e58e906eb0b6e3c58478c0"; };
+
+  };
 
+  class FrameGraph {
+    public:
+    typedef FrameGraphRequest Request;
+    typedef FrameGraphResponse Response;
   };
 
 }
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf/tf.h	Sat Nov 12 23:54:45 2011 +0000
@@ -0,0 +1,55 @@
+/* 
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2011, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ *  * Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  * Redistributions in binary form must reproduce the above
+ *    copyright notice, this list of conditions and the following
+ *    disclaimer in the documentation and/or other materials provided
+ *    with the distribution.
+ *  * Neither the name of Willow Garage, Inc. nor the names of its
+ *    contributors may be used to endorse or promote prducts derived
+ *    from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef ROS_TF_H_
+#define ROS_TF_H_
+
+#include "geometry_msgs/TransformStamped.h"
+
+namespace tf
+{
+  
+  geometry_msgs::Quaternion createQuaternionFromYaw(double yaw)
+  {
+    geometry_msgs::Quaternion q;
+    q.x = 0;
+    q.y = 0;
+    q.z = sin(yaw * 0.5);
+    q.w = cos(yaw * 0.5);
+    return q;
+  }
+
+}
+
+#endif
--- a/tf/tfMessage.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/tf/tfMessage.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_tfMessage_h
-#define ros_tfMessage_h
+#ifndef _ROS_tf_tfMessage_h
+#define _ROS_tf_tfMessage_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "geometry_msgs/TransformStamped.h"
 
 namespace tf
@@ -13,18 +13,18 @@
   class tfMessage : public ros::Msg
   {
     public:
-      unsigned char transforms_length;
+      uint8_t transforms_length;
       geometry_msgs::TransformStamped st_transforms;
       geometry_msgs::TransformStamped * transforms;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       *(outbuffer + offset++) = transforms_length;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
       *(outbuffer + offset++) = 0;
-      for( unsigned char i = 0; i < transforms_length; i++){
+      for( uint8_t i = 0; i < transforms_length; i++){
       offset += this->transforms[i].serialize(outbuffer + offset);
       }
       return offset;
@@ -33,12 +33,12 @@
     virtual int deserialize(unsigned char *inbuffer)
     {
       int offset = 0;
-      unsigned char transforms_lengthT = *(inbuffer + offset++);
+      uint8_t transforms_lengthT = *(inbuffer + offset++);
       if(transforms_lengthT > transforms_length)
         this->transforms = (geometry_msgs::TransformStamped*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::TransformStamped));
       offset += 3;
       transforms_length = transforms_lengthT;
-      for( unsigned char i = 0; i < transforms_length; i++){
+      for( uint8_t i = 0; i < transforms_length; i++){
       offset += this->st_transforms.deserialize(inbuffer + offset);
         memcpy( &(this->transforms[i]), &(this->st_transforms), sizeof(geometry_msgs::TransformStamped));
       }
@@ -46,6 +46,7 @@
     }
 
     virtual const char * getType(){ return "tf/tfMessage"; };
+    virtual const char * getMD5(){ return "94810edda583a504dfda3829e70d7eec"; };
 
   };
 
--- a/tf/transform_broadcaster.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/tf/transform_broadcaster.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,70 +1,67 @@
-/* 
- * Software License Agreement (BSD License)
- *
- * Copyright (c) 2011, Willow Garage, Inc.
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- *  * Redistributions of source code must retain the above copyright
- *    notice, this list of conditions and the following disclaimer.
- *  * Redistributions in binary form must reproduce the above
- *    copyright notice, this list of conditions and the following
- *    disclaimer in the documentation and/or other materials provided
- *    with the distribution.
- *  * Neither the name of Willow Garage, Inc. nor the names of its
- *    contributors may be used to endorse or promote prducts derived
- *    from this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-/* 
- * Author: Michael Ferguson
- */
-
-#ifndef ros_tf_h
-#define ros_tf_h
-
-#include "tfMessage.h"
-
-namespace tf
-{
-
-  class TransformBroadcaster
-  {
-    public:
-      TransformBroadcaster() : publisher_("tf", &internal_msg)
-      {
-        nh.advertise(publisher_);
-      }
-
-      void sendTransform(geometry_msgs::TransformStamped &transform)
-      {
-        internal_msg.transforms_length = 1;
-        internal_msg.transforms = &transform;
-        publisher_.publish(&internal_msg);
-      }
-
-    private:
-      tf::tfMessage internal_msg;
-      ros::Publisher publisher_;
-  };
-
-}
-
-#endif
-
+/* 
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2011, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ *  * Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  * Redistributions in binary form must reproduce the above
+ *    copyright notice, this list of conditions and the following
+ *    disclaimer in the documentation and/or other materials provided
+ *    with the distribution.
+ *  * Neither the name of Willow Garage, Inc. nor the names of its
+ *    contributors may be used to endorse or promote prducts derived
+ *    from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef ROS_TRANSFORM_BROADCASTER_H_
+#define ROS_TRANSFORM_BROADCASTER_H_
+
+#include "tfMessage.h"
+
+namespace tf
+{
+
+  class TransformBroadcaster
+  {
+    public:
+      TransformBroadcaster() : publisher_("tf", &internal_msg) {}
+
+      void init(ros::NodeHandle &nh)
+      {
+        nh.advertise(publisher_);
+      }
+
+      void sendTransform(geometry_msgs::TransformStamped &transform)
+      {
+        internal_msg.transforms_length = 1;
+        internal_msg.transforms = &transform;
+        publisher_.publish(&internal_msg);
+      }
+
+    private:
+      tf::tfMessage internal_msg;
+      ros::Publisher publisher_;
+  };
+
+}
+
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/topic_tools/MuxAdd.h	Sat Nov 12 23:54:45 2011 +0000
@@ -0,0 +1,76 @@
+#ifndef _ROS_SERVICE_MuxAdd_h
+#define _ROS_SERVICE_MuxAdd_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace topic_tools
+{
+
+static const char MUXADD[] = "topic_tools/MuxAdd";
+
+  class MuxAddRequest : public ros::Msg
+  {
+    public:
+      char * topic;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t * length_topic = (uint32_t *)(outbuffer + offset);
+      *length_topic = strlen( (const char*) this->topic);
+      offset += 4;
+      memcpy(outbuffer + offset, this->topic, *length_topic);
+      offset += *length_topic;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_topic = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_topic; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_topic-1]=0;
+      this->topic = (char *)(inbuffer + offset-1);
+      offset += length_topic;
+     return offset;
+    }
+
+    virtual const char * getType(){ return MUXADD; };
+    virtual const char * getMD5(){ return "d8f94bae31b356b24d0427f80426d0c3"; };
+
+  };
+
+  class MuxAddResponse : public ros::Msg
+  {
+    public:
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    virtual const char * getType(){ return MUXADD; };
+    virtual const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class MuxAdd {
+    public:
+    typedef MuxAddRequest Request;
+    typedef MuxAddResponse Response;
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/topic_tools/MuxDelete.h	Sat Nov 12 23:54:45 2011 +0000
@@ -0,0 +1,76 @@
+#ifndef _ROS_SERVICE_MuxDelete_h
+#define _ROS_SERVICE_MuxDelete_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace topic_tools
+{
+
+static const char MUXDELETE[] = "topic_tools/MuxDelete";
+
+  class MuxDeleteRequest : public ros::Msg
+  {
+    public:
+      char * topic;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t * length_topic = (uint32_t *)(outbuffer + offset);
+      *length_topic = strlen( (const char*) this->topic);
+      offset += 4;
+      memcpy(outbuffer + offset, this->topic, *length_topic);
+      offset += *length_topic;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_topic = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_topic; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_topic-1]=0;
+      this->topic = (char *)(inbuffer + offset-1);
+      offset += length_topic;
+     return offset;
+    }
+
+    virtual const char * getType(){ return MUXDELETE; };
+    virtual const char * getMD5(){ return "d8f94bae31b356b24d0427f80426d0c3"; };
+
+  };
+
+  class MuxDeleteResponse : public ros::Msg
+  {
+    public:
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    virtual const char * getType(){ return MUXDELETE; };
+    virtual const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class MuxDelete {
+    public:
+    typedef MuxDeleteRequest Request;
+    typedef MuxDeleteResponse Response;
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/topic_tools/MuxList.h	Sat Nov 12 23:54:45 2011 +0000
@@ -0,0 +1,92 @@
+#ifndef _ROS_SERVICE_MuxList_h
+#define _ROS_SERVICE_MuxList_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace topic_tools
+{
+
+static const char MUXLIST[] = "topic_tools/MuxList";
+
+  class MuxListRequest : public ros::Msg
+  {
+    public:
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    virtual const char * getType(){ return MUXLIST; };
+    virtual const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
+
+  };
+
+  class MuxListResponse : public ros::Msg
+  {
+    public:
+      uint8_t topics_length;
+      char* st_topics;
+      char* * topics;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = topics_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( uint8_t i = 0; i < topics_length; i++){
+      uint32_t * length_topicsi = (uint32_t *)(outbuffer + offset);
+      *length_topicsi = strlen( (const char*) this->topics[i]);
+      offset += 4;
+      memcpy(outbuffer + offset, this->topics[i], *length_topicsi);
+      offset += *length_topicsi;
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint8_t topics_lengthT = *(inbuffer + offset++);
+      if(topics_lengthT > topics_length)
+        this->topics = (char**)realloc(this->topics, topics_lengthT * sizeof(char*));
+      offset += 3;
+      topics_length = topics_lengthT;
+      for( uint8_t i = 0; i < topics_length; i++){
+      uint32_t length_st_topics = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_topics; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_st_topics-1]=0;
+      this->st_topics = (char *)(inbuffer + offset-1);
+      offset += length_st_topics;
+        memcpy( &(this->topics[i]), &(this->st_topics), sizeof(char*));
+      }
+     return offset;
+    }
+
+    virtual const char * getType(){ return MUXLIST; };
+    virtual const char * getMD5(){ return "b0eef9a05d4e829092fc2f2c3c2aad3d"; };
+
+  };
+
+  class MuxList {
+    public:
+    typedef MuxListRequest Request;
+    typedef MuxListResponse Response;
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/topic_tools/MuxSelect.h	Sat Nov 12 23:54:45 2011 +0000
@@ -0,0 +1,90 @@
+#ifndef _ROS_SERVICE_MuxSelect_h
+#define _ROS_SERVICE_MuxSelect_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace topic_tools
+{
+
+static const char MUXSELECT[] = "topic_tools/MuxSelect";
+
+  class MuxSelectRequest : public ros::Msg
+  {
+    public:
+      char * topic;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t * length_topic = (uint32_t *)(outbuffer + offset);
+      *length_topic = strlen( (const char*) this->topic);
+      offset += 4;
+      memcpy(outbuffer + offset, this->topic, *length_topic);
+      offset += *length_topic;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_topic = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_topic; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_topic-1]=0;
+      this->topic = (char *)(inbuffer + offset-1);
+      offset += length_topic;
+     return offset;
+    }
+
+    virtual const char * getType(){ return MUXSELECT; };
+    virtual const char * getMD5(){ return "d8f94bae31b356b24d0427f80426d0c3"; };
+
+  };
+
+  class MuxSelectResponse : public ros::Msg
+  {
+    public:
+      char * prev_topic;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      uint32_t * length_prev_topic = (uint32_t *)(outbuffer + offset);
+      *length_prev_topic = strlen( (const char*) this->prev_topic);
+      offset += 4;
+      memcpy(outbuffer + offset, this->prev_topic, *length_prev_topic);
+      offset += *length_prev_topic;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_prev_topic = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_prev_topic; ++k){
+          inbuffer[k-1]=inbuffer[k];
+      }
+      inbuffer[offset+length_prev_topic-1]=0;
+      this->prev_topic = (char *)(inbuffer + offset-1);
+      offset += length_prev_topic;
+     return offset;
+    }
+
+    virtual const char * getType(){ return MUXSELECT; };
+    virtual const char * getMD5(){ return "3db0a473debdbafea387c9e49358c320"; };
+
+  };
+
+  class MuxSelect {
+    public:
+    typedef MuxSelectRequest Request;
+    typedef MuxSelectResponse Response;
+  };
+
+}
+#endif
\ No newline at end of file