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:
Sun Oct 16 07:19:36 2011 +0000
Parent:
0:77afd7560544
Child:
2:bb6bb835fde4
Commit message:
This program supported the revision of 143 of rosserial.
And the bug fix of receive of array data.

Changed in this revision

MODSERIAL.lib Show annotated file Show diff for this revision Revisions of this file
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
duration.cpp 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
main.cpp Show annotated file Show diff for this revision Revisions of this file
mbed.bld 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 annotated file 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 annotated file 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/ros_impl.h Show diff for this revision Revisions of this file
ros/rosserial_ids.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
ros/time.h Show annotated file 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/TopicInfo.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/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/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/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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MODSERIAL.lib	Sun Oct 16 07:19:36 2011 +0000
@@ -0,0 +1,1 @@
+http://mbed.org/users/AjK/code/MODSERIAL/#af2af4c61c2f
--- a/MbedHardware.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/MbedHardware.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
 /*
- * mbedHardware
+ * MbedHardware
  *
  *  Created on: Aug 17, 2011
  *      Author: nucho
@@ -9,10 +9,12 @@
 #define MBEDHARDWARE_H_
 
 #include"mbed.h"
+#include"MODSERIAL.h"
+
 
 class MbedHardware {
 public:
-    MbedHardware(Serial* io , long baud= 57600)
+    MbedHardware(MODSERIAL* io , int baud= 57600)
             :iostream(*io){
         baud_ = baud;
         t.start();
@@ -29,7 +31,7 @@
         t.start();
     }
 
-    void setBaud(long baud) {
+    void setBaud(int baud) {
         this->baud_= baud;
     }
 
@@ -57,8 +59,8 @@
     }
 
 protected:
-    long baud_;
-    Serial iostream;
+    int baud_;
+    MODSERIAL iostream;
     Timer t;
 };
 
--- a/dianostic_msgs/DiagnosticArray.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/dianostic_msgs/DiagnosticArray.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_DiagnosticArray_h
-#define ros_DiagnosticArray_h
+#ifndef ros_diagnostic_msgs_DiagnosticArray_h
+#define ros_diagnostic_msgs_DiagnosticArray_h
 
 #include <stdint.h>
 #include <string.h>
@@ -8,50 +8,48 @@
 #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;
+    unsigned char 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) {
+        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 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);
+        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 const char * getType(){ return "diagnostic_msgs/DiagnosticArray"; };
+    virtual const char * getType() {
+        return "diagnostic_msgs/DiagnosticArray";
+    };
 
-  };
+};
 
 }
 #endif
\ No newline at end of file
--- a/dianostic_msgs/DiagnosticStatus.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/dianostic_msgs/DiagnosticStatus.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_DiagnosticStatus_h
-#define ros_DiagnosticStatus_h
+#ifndef ros_diagnostic_msgs_DiagnosticStatus_h
+#define ros_diagnostic_msgs_DiagnosticStatus_h
 
 #include <stdint.h>
 #include <string.h>
@@ -7,108 +7,106 @@
 #include "../ros/msg.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:
+    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 };
 
-    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) {
+        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 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;
+        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 const char * getType(){ return "diagnostic_msgs/DiagnosticStatus"; };
+    virtual const char * getType() {
+        return "diagnostic_msgs/DiagnosticStatus";
+    };
 
-  };
+};
 
 }
 #endif
\ No newline at end of file
--- a/dianostic_msgs/KeyValue.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/dianostic_msgs/KeyValue.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,61 +1,59 @@
-#ifndef ros_KeyValue_h
-#define ros_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"
 
-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) {
+        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 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";
+    };
 
-  };
+};
 
 }
 #endif
\ No newline at end of file
--- a/duration.cpp	Fri Aug 19 09:06:30 2011 +0000
+++ b/duration.cpp	Sun Oct 16 07:19:36 2011 +0000
@@ -32,13 +32,8 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-/* 
- * Author: Michael Ferguson
- */
-
+#include <math.h>
 #include "ros/duration.h"
-#include <math.h>
-
 
 namespace ros
 {
@@ -83,4 +78,4 @@
     return *this;
   }
 
-}
+}
\ No newline at end of file
--- a/geometry_msgs/Point.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/geometry_msgs/Point.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,111 +1,109 @@
-#ifndef ros_Point_h
-#define ros_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"
 
-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) {
+        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 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;
+        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 const char * getType(){ return "geometry_msgs/Point"; };
+    virtual const char * getType() {
+        return "geometry_msgs/Point";
+    };
 
-  };
+};
 
 }
 #endif
\ No newline at end of file
--- a/geometry_msgs/Point32.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/geometry_msgs/Point32.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_Point32_h
-#define ros_Point32_h
+#ifndef ros_geometry_msgs_Point32_h
+#define ros_geometry_msgs_Point32_h
 
 #include <stdint.h>
 #include <string.h>
--- a/geometry_msgs/PointStamped.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/geometry_msgs/PointStamped.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_PointStamped_h
-#define ros_PointStamped_h
+#ifndef ros_geometry_msgs_PointStamped_h
+#define ros_geometry_msgs_PointStamped_h
 
 #include <stdint.h>
 #include <string.h>
--- a/geometry_msgs/Polygon.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/geometry_msgs/Polygon.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_Polygon_h
-#define ros_Polygon_h
+#ifndef ros_geometry_msgs_Polygon_h
+#define ros_geometry_msgs_Polygon_h
 
 #include <stdint.h>
 #include <string.h>
@@ -7,47 +7,45 @@
 #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:
+    unsigned char 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) {
+        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 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;
+        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 const char * getType(){ return "geometry_msgs/Polygon"; };
+    virtual const char * getType() {
+        return "geometry_msgs/Polygon";
+    };
 
-  };
+};
 
 }
 #endif
\ No newline at end of file
--- a/geometry_msgs/PolygonStamped.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/geometry_msgs/PolygonStamped.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_PolygonStamped_h
-#define ros_PolygonStamped_h
+#ifndef ros_geometry_msgs_PolygonStamped_h
+#define ros_geometry_msgs_PolygonStamped_h
 
 #include <stdint.h>
 #include <string.h>
--- a/geometry_msgs/Pose.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/geometry_msgs/Pose.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_Pose_h
-#define ros_Pose_h
+#ifndef ros_geometry_msgs_Pose_h
+#define ros_geometry_msgs_Pose_h
 
 #include <stdint.h>
 #include <string.h>
--- a/geometry_msgs/Pose2D.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/geometry_msgs/Pose2D.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_Pose2D_h
-#define ros_Pose2D_h
+#ifndef ros_geometry_msgs_Pose2D_h
+#define ros_geometry_msgs_Pose2D_h
 
 #include <stdint.h>
 #include <string.h>
--- a/geometry_msgs/PoseArray.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/geometry_msgs/PoseArray.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_PoseArray_h
-#define ros_PoseArray_h
+#ifndef ros_geometry_msgs_PoseArray_h
+#define ros_geometry_msgs_PoseArray_h
 
 #include <stdint.h>
 #include <string.h>
--- a/geometry_msgs/PoseStamped.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/geometry_msgs/PoseStamped.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_PoseStamped_h
-#define ros_PoseStamped_h
+#ifndef ros_geometry_msgs_PoseStamped_h
+#define ros_geometry_msgs_PoseStamped_h
 
 #include <stdint.h>
 #include <string.h>
--- a/geometry_msgs/PoseWithCovariance.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/geometry_msgs/PoseWithCovariance.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_PoseWithCovariance_h
-#define ros_PoseWithCovariance_h
+#ifndef ros_geometry_msgs_PoseWithCovariance_h
+#define ros_geometry_msgs_PoseWithCovariance_h
 
 #include <stdint.h>
 #include <string.h>
--- a/geometry_msgs/PoseWithCovarianceStamped.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/geometry_msgs/PoseWithCovarianceStamped.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_PoseWithCovarianceStamped_h
-#define ros_PoseWithCovarianceStamped_h
+#ifndef ros_geometry_msgs_PoseWithCovarianceStamped_h
+#define ros_geometry_msgs_PoseWithCovarianceStamped_h
 
 #include <stdint.h>
 #include <string.h>
--- a/geometry_msgs/Quaternion.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/geometry_msgs/Quaternion.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_Quaternion_h
-#define ros_Quaternion_h
+#ifndef ros_geometry_msgs_Quaternion_h
+#define ros_geometry_msgs_Quaternion_h
 
 #include <stdint.h>
 #include <string.h>
--- a/geometry_msgs/QuaternionStamped.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/geometry_msgs/QuaternionStamped.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,6 @@
-#ifndef ros_QuaternionStamped_h
-#define ros_QuaternionStamped_h
+#ifndef ros_geometry_msgs_QuaternionStamped_h
+#define ros_geometry_msgs_QuaternionStamped_h
+
 
 #include <stdint.h>
 #include <string.h>
--- a/geometry_msgs/Transform.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/geometry_msgs/Transform.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_Transform_h
-#define ros_Transform_h
+#ifndef ros_geometry_msgs_Transform_h
+#define ros_geometry_msgs_Transform_h
 
 #include <stdint.h>
 #include <string.h>
--- a/geometry_msgs/TransformStamped.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/geometry_msgs/TransformStamped.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_TransformStamped_h
-#define ros_TransformStamped_h
+#ifndef ros_geometry_msgs_TransformStamped_h
+#define ros_geometry_msgs_TransformStamped_h
 
 #include <stdint.h>
 #include <string.h>
--- a/geometry_msgs/Twist.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/geometry_msgs/Twist.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_Twist_h
-#define ros_Twist_h
+#ifndef ros_geometry_msgs_Twist_h
+#define ros_geometry_msgs_Twist_h
 
 #include <stdint.h>
 #include <string.h>
--- a/geometry_msgs/TwistStamped.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/geometry_msgs/TwistStamped.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_TwistStamped_h
-#define ros_TwistStamped_h
+#ifndef ros_geometry_msgs_TwistStamped_h
+#define ros_geometry_msgs_TwistStamped_h
 
 #include <stdint.h>
 #include <string.h>
--- a/geometry_msgs/TwistWithCovariance.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/geometry_msgs/TwistWithCovariance.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_TwistWithCovariance_h
-#define ros_TwistWithCovariance_h
+#ifndef ros_geometry_msgs_TwistWithCovariance_h
+#define ros_geometry_msgs_TwistWithCovariance_h
 
 #include <stdint.h>
 #include <string.h>
--- a/geometry_msgs/TwistWithCovarianceStamped.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/geometry_msgs/TwistWithCovarianceStamped.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_TwistWithCovarianceStamped_h
-#define ros_TwistWithCovarianceStamped_h
+#ifndef ros_geometry_msgs_TwistWithCovarianceStamped_h
+#define ros_geometry_msgs_TwistWithCovarianceStamped_h
 
 #include <stdint.h>
 #include <string.h>
--- a/geometry_msgs/Vector3.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/geometry_msgs/Vector3.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_Vector3_h
-#define ros_Vector3_h
+#ifndef ros_geometry_msgs_Vector3_h
+#define ros_geometry_msgs_Vector3_h
 
 #include <stdint.h>
 #include <string.h>
--- a/geometry_msgs/Vector3Stamped.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/geometry_msgs/Vector3Stamped.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_Vector3Stamped_h
-#define ros_Vector3Stamped_h
+#ifndef ros_geometry_msgs_Vector3Stamped_h
+#define ros_geometry_msgs_Vector3Stamped_h
 
 #include <stdint.h>
 #include <string.h>
--- a/geometry_msgs/Wrench.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/geometry_msgs/Wrench.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,6 @@
-#ifndef ros_Wrench_h
-#define ros_Wrench_h
+#ifndef ros_geometry_msgs_Wrench_h
+#define ros_geometry_msgs_Wrench_h
+
 
 #include <stdint.h>
 #include <string.h>
--- a/geometry_msgs/WrenchStamped.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/geometry_msgs/WrenchStamped.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_WrenchStamped_h
-#define ros_WrenchStamped_h
+#ifndef ros_geometry_msgs_WrenchStamped_h
+#define ros_geometry_msgs_WrenchStamped_h
 
 #include <stdint.h>
 #include <string.h>
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main.cpp	Sun Oct 16 07:19:36 2011 +0000
@@ -0,0 +1,27 @@
+/*
+ * rosserial Publisher Example
+ * Prints "hello world!"
+ */
+
+#include"mbed.h"
+#include <ros.h>
+#include <std_msgs/String.h>
+
+ros::NodeHandle  nh;
+
+std_msgs::String str_msg;
+ros::Publisher chatter("chatter", &str_msg);
+
+char hello[13] = "hello world!";
+
+int main() {
+    nh.initNode();
+    nh.advertise(chatter);
+
+    while (1) {
+        str_msg.data = hello;
+        chatter.publish( &str_msg );
+        nh.spinOnce();
+        wait_ms(1000);
+    }
+}
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed.bld	Sun Oct 16 07:19:36 2011 +0000
@@ -0,0 +1,1 @@
+http://mbed.org/users/mbed_official/code/mbed/builds/63bcd7ba4912
--- a/nav_msgs/GridCells.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/nav_msgs/GridCells.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_GridCells_h
-#define ros_GridCells_h
+#ifndef ros_nav_msgs_GridCells_h
+#define ros_nav_msgs_GridCells_h
 
 #include <stdint.h>
 #include <string.h>
--- a/nav_msgs/MapMetaData.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/nav_msgs/MapMetaData.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_MapMetaData_h
-#define ros_MapMetaData_h
+#ifndef ros_nav_msgs_MapMetaData_h
+#define ros_nav_msgs_MapMetaData_h
 
 #include <stdint.h>
 #include <string.h>
--- a/nav_msgs/OccupancyGrid.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/nav_msgs/OccupancyGrid.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_OccupancyGrid_h
-#define ros_OccupancyGrid_h
+#ifndef ros_nav_msgs_OccupancyGrid_h
+#define ros_nav_msgs_OccupancyGrid_h
 
 #include <stdint.h>
 #include <string.h>
--- a/nav_msgs/Odometry.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/nav_msgs/Odometry.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_Odometry_h
-#define ros_Odometry_h
+#ifndef ros_nav_msgs_Odometry_h
+#define ros_nav_msgs_Odometry_h
 
 #include <stdint.h>
 #include <string.h>
--- a/nav_msgs/Path.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/nav_msgs/Path.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_Path_h
-#define ros_Path_h
+#ifndef ros_nav_msgs_Path_h
+#define ros_nav_msgs_Path_h
 
 #include <stdint.h>
 #include <string.h>
--- a/ros.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/ros.h	Sun Oct 16 07:19:36 2011 +0000
@@ -32,15 +32,10 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-/* 
- * ROS definitions for Arduino
- * Author: Michael Ferguson
- */
-
 #ifndef ros_h
 #define ros_h
 
-#include "ros/ros_impl.h"
+#include "ros/node_handle.h"
 #include "MbedHardware.h"
 
 namespace ros
--- a/ros/duration.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/ros/duration.h	Sun Oct 16 07:19:36 2011 +0000
@@ -32,16 +32,11 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-/* 
- * Author: Michael Ferguson
- */
+#ifndef ROS_DURATION_H_
+#define ROS_DURATION_H_
 
-#ifndef ros_duration_h_included
-#define ros_duration_h_included
+namespace ros {
 
-
-namespace ros
-{
   void normalizeSecNSecSigned(long& sec, long& nsec);
 
   class Duration
@@ -58,10 +53,8 @@
       Duration& operator+=(const Duration &rhs);
       Duration& operator-=(const Duration &rhs);
       Duration& operator*=(double scale);
-      
   };
 
 }
 
 #endif
-
--- a/ros/msg.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/ros/msg.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,22 +1,52 @@
-/*
- * Msg.h
+/* 
+ * 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:
  *
- *  Created on: Aug 5, 2011
- *      Author: astambler
+ *  * 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_H_
 #define ROS_MSG_H_
 
+
 namespace ros {
-/* Base Message Type */
-class Msg {
-public:
-    virtual int serialize(unsigned char *outbuffer) = 0;
-    virtual int deserialize(unsigned char *data) = 0;
-    virtual const char * getType() = 0;
 
-};
+  /* Base Message Type */
+  class Msg
+  {
+    public:
+      virtual int serialize(unsigned char *outbuffer) = 0;
+      virtual int deserialize(unsigned char *data) = 0;
+      virtual const char * getType() = 0;
+  };
+
 }
 
-#endif /* MSG_H_ */
+#endif
\ No newline at end of file
--- a/ros/msg_receiver.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/ros/msg_receiver.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,27 +1,55 @@
-/*
- * msg_receiver.h
+/* 
+ * 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:
  *
- *  Created on: Aug 5, 2011
- *      Author: astambler
+ *  * 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 MSG_RECEIVER_H_
-#define MSG_RECEIVER_H_
+#ifndef ROS_MSG_RECEIVER_H_
+#define ROS_MSG_RECEIVER_H_
 
-namespace ros{
+namespace ros {
 
-/* Base class for objects recieving messages (Services and Subscribers) */
+  /* Base class for objects recieving messages (Services and Subscribers) */
   class MsgReceiver
   {
     public:
-        virtual void receive(unsigned char *data)=0;
+      virtual void receive(unsigned char *data)=0;
 
-        //Distinguishes between different receiver types
-        virtual int _getType()=0;
-        virtual const char * getMsgType()=0;
-        int id_;
-        const char * topic_;
+      //Distinguishes between different receiver types
+      virtual int _getType()=0;
+      virtual const char * getMsgType()=0;
+      short id_;
+      const char * topic_;
   };
+
 }
 
-#endif /* MSG_RECEIVER_H_ */
+#endif
\ No newline at end of file
--- a/ros/node_handle.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/ros/node_handle.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,4 @@
 /*
- * NodeHandle.h
  * Software License Agreement (BSD License)
  *
  * Copyright (c) 2011, Willow Garage, Inc.
@@ -33,11 +32,6 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-/*
- *
- * Author: Michael Ferguson , Adam Stambler
- */
-
 #ifndef ROS_NODE_HANDLE_H_
 #define ROS_NODE_HANDLE_H_
 
@@ -57,7 +51,6 @@
 #define MODE_MESSAGE        6
 #define MODE_CHECKSUM       7
 
-
 #define MSG_TIMEOUT 20  //20 milliseconds to recieve all of message data
 
 #include "node_output.h"
@@ -68,16 +61,17 @@
 #include "rosserial_ids.h"
 #include "service_server.h"
 
-
 namespace ros {
 
 using rosserial_msgs::TopicInfo;
 
 /* Node Handle */
-template<class Hardware, int MAX_SUBSCRIBERS=25, int MAX_PUBLISHERS=25,
-int INPUT_SIZE=512, int OUTPUT_SIZE=512>
+template<class Hardware,
+int MAX_SUBSCRIBERS=25,
+int MAX_PUBLISHERS=25,
+int INPUT_SIZE=512,
+int OUTPUT_SIZE=512>
 class NodeHandle_ {
-
 protected:
     Hardware hardware_;
     NodeOutput<Hardware, OUTPUT_SIZE> no_;
@@ -93,12 +87,11 @@
     Publisher * publishers[MAX_PUBLISHERS];
     MsgReceiver * receivers[MAX_SUBSCRIBERS];
 
-    /******************************
-     *  Setup Functions
+    /*
+     * Setup Functions
      */
 public:
-    NodeHandle_() : no_(&hardware_) {
-    }
+    NodeHandle_() : no_(&hardware_) {}
 
     Hardware* getHardware() {
         return &hardware_;
@@ -111,12 +104,12 @@
         bytes_ = 0;
         index_ = 0;
         topic_ = 0;
+        checksum_=0;
+
         total_receivers=0;
     };
 
-
 protected:
-
     //State machine variables for spinOnce
     int mode_;
     int bytes_;
@@ -126,39 +119,35 @@
 
     int total_receivers;
 
-
     /* used for syncing the time */
     unsigned long last_sync_time;
     unsigned long last_sync_receive_time;
     unsigned long last_msg_timeout_time;
 
     bool registerReceiver(MsgReceiver* rcv) {
-        if (total_receivers >= MAX_SUBSCRIBERS) return false;
+        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() {
-        /* restart if timed-out */
 
+        /* restart if timed out */
         unsigned long c_time = hardware_.time();
-
-        if (  (c_time - last_sync_receive_time) > (SYNC_SECONDS*2200) ) {
+        if ( (c_time - last_sync_receive_time) > (SYNC_SECONDS*2200) ) {
             no_.setConfigured(false);
         }
 
-        if ( mode_ != MODE_FIRST_FF) { //we are still in the midde of
-            //the message, and the message's
-            //timeout has already past, reset
-            //state machine
+        /* reset if message has timed out */
+        if ( mode_ != MODE_FIRST_FF) {
             if (c_time > last_msg_timeout_time) {
                 mode_ = MODE_FIRST_FF;
             }
@@ -166,8 +155,8 @@
 
         /* while available buffer, read data */
         while ( true ) {
-            short data = hardware_.read();
-            if ( data < 0 )
+            int data = hardware_.read();
+            if ( data < 0 )//no data
                 break;
             checksum_ += data;
             if ( mode_ == MODE_MESSAGE ) {      /* message data being recieved */
@@ -230,15 +219,14 @@
         }
     }
 
-
     /* Are we connected to the PC? */
     bool connected() {
         return no_.configured();
     };
 
-    /**************************************************************
+    /*
      * Time functions
-     **************************************************************/
+     */
 
     void requestSyncTime() {
         std_msgs::Time t;
@@ -259,8 +247,6 @@
         last_sync_receive_time = hardware_.time();
     }
 
-
-
     Time now() {
         unsigned long ms = hardware_.time();
         Time current_time;
@@ -277,8 +263,10 @@
         normalizeSecNSec(sec_offset, nsec_offset);
     }
 
+    /*
+     * Registration
+     */
 
-    /***************   Registeration    *****************************/
     bool advertise(Publisher & p) {
         int i;
         for (i = 0; i < MAX_PUBLISHERS; i++) {
@@ -306,7 +294,6 @@
 
     void negotiateTopics() {
         no_.setConfigured(true);
-
         rosserial_msgs::TopicInfo ti;
         int i;
         for (i = 0; i < MAX_PUBLISHERS; i++) {
@@ -330,6 +317,7 @@
     /*
      * Logging
      */
+
 private:
     void log(char byte, const char * msg) {
         rosserial_msgs::Log l;
@@ -337,6 +325,7 @@
         l.msg = (char*)msg;
         this->no_.publish(rosserial_msgs::TopicInfo::ID_LOG, &l);
     }
+
 public:
     void logdebug(const char* msg) {
         log(rosserial_msgs::Log::DEBUG, msg);
@@ -355,12 +344,14 @@
     }
 
 
-    /****************************************
+    /*
      * Retrieve Parameters
-     *****************************************/
+     */
+
 private:
     bool param_recieved;
     rosserial_msgs::RequestParamResponse req_param_resp;
+
     bool requestParam(const char * name, int time_out =  1000) {
         param_recieved = false;
         rosserial_msgs::RequestParamRequest req;
@@ -373,12 +364,14 @@
         }
         return true;
     }
+
 public:
     bool getParam(const char* name, int* param, int length =1) {
         if (requestParam(name) ) {
             if (length == req_param_resp.ints_length) {
                 //copy it over
-                for (int i=0; i<length; i++) param[i] = req_param_resp.ints[i];
+                for (int i=0; i<length; i++)
+                    param[i] = req_param_resp.ints[i];
                 return true;
             }
         }
@@ -388,7 +381,8 @@
         if (requestParam(name) ) {
             if (length == req_param_resp.floats_length) {
                 //copy it over
-                for (int i=0; i<length; i++) param[i] = req_param_resp.floats[i];
+                for (int i=0; i<length; i++)
+                    param[i] = req_param_resp.floats[i];
                 return true;
             }
         }
@@ -398,18 +392,15 @@
         if (requestParam(name) ) {
             if (length == req_param_resp.strings_length) {
                 //copy it over
-                for (int i=0; i<length; i++) strcpy(param[i],req_param_resp.strings[i]);
+                for (int i=0; i<length; i++)
+                    strcpy(param[i],req_param_resp.strings[i]);
                 return true;
             }
         }
         return false;
-
     }
-
 };
 
-
-
 }
 
-#endif /* NODEHANDLE_H_ */
+#endif
\ No newline at end of file
--- a/ros/node_output.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/ros/node_output.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,28 +1,56 @@
 /*
- * NodeOutput.h
+ * 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:
  *
- *  Created on: Aug 5, 2011
- *      Author: astambler
+ *  * 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 NODEOUTPUT_H_
-#define NODEOUTPUT_H_
+#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
  */
-
-#include "msg.h"
-
-namespace ros {
-
 class NodeOutput_ {
 public:
     virtual int publish(short id, Msg* msg)=0;
 };
 
-
 template<class Hardware, int OUTSIZE =512>
 class NodeOutput : public NodeOutput_ {
 
@@ -38,6 +66,7 @@
     }
 
     NodeOutput() {};
+
     void setHardware(Hardware* h) {
         hardware_  = h;
         configured_=false;
@@ -50,10 +79,10 @@
         return configured_;
     };
 
-    virtual int  publish(short id, Msg * msg) {
-        if (!configured_) return 0;
+    virtual int publish(short id, Msg * msg) {
+        wait_ms(1);
+        if (!configured_)return 0;
 
-        //short test_id,test_off;
         /* serialize message */
         short l = msg->serialize(message_out+6);
 
@@ -69,11 +98,14 @@
         short chk = 0;
         for (int i =2; i<l+6; i++)
             chk += message_out[i];
-        message_out[6+l] = 255 - (chk%256);
+        l += 6;
+        message_out[l++] = 255 - (chk%256);
 
-        hardware_->write(message_out, 6+l+1);
-        return 1;
+        hardware_->write(message_out, l);
+        return l;
     }
 };
+
 }
-#endif /* NODEOUTPUT_H_ */
+
+#endif
\ No newline at end of file
--- a/ros/publisher.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/ros/publisher.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,8 +1,35 @@
-/*
- * publisher.h
+/* 
+ * 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:
  *
- *  Created on: Aug 5, 2011
- *      Author: astambler
+ *  * 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 PUBLISHER_H_
@@ -11,8 +38,8 @@
 #include "node_output.h"
 
 namespace ros{
+
   /* Generic Publisher */
-
   class Publisher
   {
     public:
@@ -24,11 +51,12 @@
       const char * topic_;
 
       Msg *msg_;
-      int id_;
+      short id_;
       NodeOutput_* no_;
+
   };
 
 }
 
 
-#endif /* PUBLISHER_H_ */
+#endif
\ No newline at end of file
--- a/ros/ros_impl.h	Fri Aug 19 09:06:30 2011 +0000
+++ /dev/null	Thu Jan 01 00:00:00 1970 +0000
@@ -1,44 +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.
- */
-
-/* 
- * Author: Michael Ferguson , Adam Stambler
- */
-
-#ifndef ros_lib_h
-#define ros_lib_h
-
-#include "node_handle.h"
-
-#endif
--- a/ros/rosserial_ids.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/ros/rosserial_ids.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,16 +1,43 @@
-/*
- * rosserial_ids.h
+/* 
+ * 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:
  *
- *  Created on: Aug 5, 2011
- *      Author: astambler
+ *  * 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 ROSSERIAL_IDS_H_
-#define ROSSERIAL_IDS_H_
+#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 /* ROSSERIAL_IDS_H_ */
+#endif
\ No newline at end of file
--- a/ros/service_server.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/ros/service_server.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,54 +1,81 @@
-/*
- * service_server.h
+/* 
+ * 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:
  *
- *  Created on: Aug 5, 2011
- *      Author: astambler
+ *  * 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 SERVICE_SERVER_H_
-#define SERVICE_SERVER_H_
-
+#ifndef ROS_SERVICE_SERVER_H_
+#define ROS_SERVICE_SERVER_H_
 
 #include "node_output.h"
 
-namespace ros{
-template<typename SrvRequest , typename SrvResponse>
+namespace ros {
+
+  template<typename SrvRequest , typename SrvResponse>
   class ServiceServer : MsgReceiver{
-  public:
+    public:
       typedef void(*CallbackT)(const SrvRequest&,  SrvResponse&);
 
-  private:
-      CallbackT cb_;
-
-  public:
       ServiceServer(const char* topic_name, CallbackT cb){
-          this->topic_ = topic_name;
-          this->cb_ = cb;
+        this->topic_ = topic_name;
+        this->cb_ = cb;
       }
 
       ServiceServer(ServiceServer& srv){
-          this->topic_ = srv.topic_;
-          this->cb_ = srv.cb_;
-      }
-      virtual void receive(unsigned char * data){
-          req.deserialize(data);
-          this->cb_(req, resp);
-          no_->publish(id_, &resp);
+        this->topic_ = srv.topic_;
+        this->cb_ = srv.cb_;
       }
 
-    virtual int _getType(){
+      virtual void receive(unsigned char * data){
+        req.deserialize(data);
+        this->cb_(req, resp);
+        no_->publish(id_, &resp);
+      }
+
+      virtual int _getType(){
         return 3;
-    }
-    virtual const char * getMsgType(){
+      }
+     
+      virtual const char * getMsgType(){
         return req.getType();
-    }
+      }
 
       SrvRequest req;
       SrvResponse resp;
       NodeOutput_ * no_;
 
+    private:
+      CallbackT cb_;
   };
+
 }
 
-#endif /* SERVICE_SERVER_H_ */
+#endif
\ No newline at end of file
--- a/ros/subscriber.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/ros/subscriber.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,42 +1,73 @@
-/*
- * subscriber.h
+/* 
+ * 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:
  *
- *  Created on: Aug 5, 2011
- *      Author: astambler
+ *  * 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 SUBSCRIBER_H_
-#define SUBSCRIBER_H_
+#ifndef ROS_SUBSCRIBER_H_
+#define ROS_SUBSCRIBER_H_
 
 #include "rosserial_ids.h"
 #include "msg_receiver.h"
-namespace ros{
+
+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.
- */
-template<typename MsgT>
-class Subscriber: public MsgReceiver{
-  public:
-
+  /* 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.
+   */
+  template<typename MsgT>
+  class Subscriber: public MsgReceiver{
+    public:
       typedef void(*CallbackT)(const MsgT&);
+      MsgT msg;
 
       Subscriber(const char * topic_name, CallbackT msgCB){
-      topic_ = topic_name;
-      cb_= msgCB;
-    }
-    MsgT msg;
-    virtual void receive(unsigned char* data){
-      msg.deserialize(data);
-      this->cb_(msg);
+        topic_ = topic_name;
+        cb_= msgCB;
+      }
+
+      virtual void receive(unsigned char* data){
+        msg.deserialize(data);
+        this->cb_(msg);
       }
-    virtual const char * getMsgType(){return this->msg.getType();}
-    virtual int _getType(){return TOPIC_SUBSCRIBERS;}
-  private:
-    CallbackT cb_;
-};
+
+      virtual const char * getMsgType(){return this->msg.getType();}
+      virtual int _getType(){return TOPIC_SUBSCRIBERS;}
+
+    private:
+      CallbackT cb_;
+  };
 
 }
-#endif /* SUBSCRIBER_H_ */
+
+#endif
\ No newline at end of file
--- a/ros/time.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/ros/time.h	Sun Oct 16 07:19:36 2011 +0000
@@ -32,21 +32,15 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-/*
- * Author: Michael Ferguson
- */
-
-#ifndef ros_time_h_included
-#define ros_time_h_included
+#ifndef ROS_TIME_H_
+#define ROS_TIME_H_
 
 #include <ros/duration.h>
 #include <math.h>
 
-
 namespace ros {
 void normalizeSecNSec(unsigned long &sec, unsigned long &nsec);
 
-
 class Time {
 public:
     unsigned long sec, nsec;
@@ -81,8 +75,8 @@
         return a;
     }
 
+};
 
-};
 }
 
-#endif
+#endif
\ No newline at end of file
--- a/rosserial_msgs/Log.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/rosserial_msgs/Log.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_Log_h
-#define ros_Log_h
+#ifndef ros_rosserial_msgs_Log_h
+#define ros_rosserial_msgs_Log_h
 
 #include <stdint.h>
 #include <string.h>
--- a/rosserial_msgs/TopicInfo.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/rosserial_msgs/TopicInfo.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,20 +1,19 @@
-#ifndef ros_TopicInfo_h
-#define ros_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"
-
 namespace rosserial_msgs
 {
-
   class TopicInfo : public ros::Msg
   {
     public:
       unsigned short topic_id;
       char * topic_name;
       char * message_type;
+      char * md5_checksum;
       enum { ID_PUBLISHER = 0 };
       enum { ID_SUBSCRIBER = 1 };
       enum { ID_SERVICE_SERVER = 2 };
@@ -27,23 +26,32 @@
     {
       int offset = 0;
       union {
-        unsigned short real;
-        unsigned short base;
+        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;
       offset += sizeof(this->topic_id);
+      
       long * length_topic_name = (long *)(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);
       *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);
+      offset += 4;
+      memcpy(outbuffer + offset, this->md5_checksum, *length_md5_checksum);
+      offset += *length_md5_checksum;
+      
       return offset;
     }
 
@@ -75,6 +83,16 @@
       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);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_md5_checksum; ++k){
+          inbuffer[k-1]=inbuffer[k];
+           }
+      inbuffer[offset+length_md5_checksum-1]=0;
+      this->md5_checksum = (char *)(inbuffer + offset-1);
+      offset += length_md5_checksum;
+
      return offset;
     }
 
--- a/std_msgs/Bool.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/Bool.h	Sun Oct 16 07:19:36 2011 +0000
@@ -19,7 +19,7 @@
       int offset = 0;
       union {
         bool real;
-        unsigned char base;
+        uint8_t base;
       } u_data;
       u_data.real = this->data;
       *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
@@ -32,7 +32,7 @@
       int offset = 0;
       union {
         bool real;
-        unsigned char base;
+        uint8_t base;
       } u_data;
       u_data.base = 0;
       u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
--- a/std_msgs/Byte.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/Byte.h	Sun Oct 16 07:19:36 2011 +0000
@@ -12,14 +12,14 @@
   class Byte : public ros::Msg
   {
     public:
-      unsigned char data;
+      uint8_t data;
 
     virtual int serialize(unsigned char *outbuffer)
     {
       int offset = 0;
       union {
-        unsigned char real;
-        unsigned char base;
+        uint8_t real;
+        uint8_t base;
       } u_data;
       u_data.real = this->data;
       *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
@@ -31,8 +31,8 @@
     {
       int offset = 0;
       union {
-        unsigned char real;
-        unsigned char base;
+        uint8_t real;
+        uint8_t base;
       } u_data;
       u_data.base = 0;
       u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
--- a/std_msgs/ByteMultiArray.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/ByteMultiArray.h	Sun Oct 16 07:19:36 2011 +0000
@@ -14,9 +14,9 @@
   {
     public:
       std_msgs::MultiArrayLayout layout;
-      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)
     {
@@ -28,8 +28,8 @@
       *(outbuffer + offset++) = 0;
       for( unsigned char i = 0; i < data_length; i++){
       union {
-        unsigned char real;
-        unsigned char base;
+        uint8_t real;
+        uint8_t base;
       } u_datai;
       u_datai.real = this->data[i];
       *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
@@ -49,8 +49,8 @@
       data_length = data_lengthT;
       for( unsigned char i = 0; i < data_length; i++){
       union {
-        unsigned char real;
-        unsigned char base;
+        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);
--- a/std_msgs/ColorRGBA.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/ColorRGBA.h	Sun Oct 16 07:19:36 2011 +0000
@@ -22,7 +22,7 @@
       int offset = 0;
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_r;
       u_r.real = this->r;
       *(outbuffer + offset + 0) = (u_r.base >> (8 * 0)) & 0xFF;
@@ -32,7 +32,7 @@
       offset += sizeof(this->r);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_g;
       u_g.real = this->g;
       *(outbuffer + offset + 0) = (u_g.base >> (8 * 0)) & 0xFF;
@@ -42,7 +42,7 @@
       offset += sizeof(this->g);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_b;
       u_b.real = this->b;
       *(outbuffer + offset + 0) = (u_b.base >> (8 * 0)) & 0xFF;
@@ -52,7 +52,7 @@
       offset += sizeof(this->b);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_a;
       u_a.real = this->a;
       *(outbuffer + offset + 0) = (u_a.base >> (8 * 0)) & 0xFF;
@@ -68,7 +68,7 @@
       int offset = 0;
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_r;
       u_r.base = 0;
       u_r.base |= ((typeof(u_r.base)) (*(inbuffer + offset + 0))) << (8 * 0);
@@ -79,7 +79,7 @@
       offset += sizeof(this->r);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_g;
       u_g.base = 0;
       u_g.base |= ((typeof(u_g.base)) (*(inbuffer + offset + 0))) << (8 * 0);
@@ -90,7 +90,7 @@
       offset += sizeof(this->g);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_b;
       u_b.base = 0;
       u_b.base |= ((typeof(u_b.base)) (*(inbuffer + offset + 0))) << (8 * 0);
@@ -101,7 +101,7 @@
       offset += sizeof(this->b);
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_a;
       u_a.base = 0;
       u_a.base |= ((typeof(u_a.base)) (*(inbuffer + offset + 0))) << (8 * 0);
--- a/std_msgs/Duration.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/Duration.h	Sun Oct 16 07:19:36 2011 +0000
@@ -19,8 +19,8 @@
     {
       int offset = 0;
       union {
-        unsigned long real;
-        unsigned long base;
+        uint32_t real;
+        uint32_t base;
       } u_sec;
       u_sec.real = this->data.sec;
       *(outbuffer + offset + 0) = (u_sec.base >> (8 * 0)) & 0xFF;
@@ -29,8 +29,8 @@
       *(outbuffer + offset + 3) = (u_sec.base >> (8 * 3)) & 0xFF;
       offset += sizeof(this->data.sec);
       union {
-        unsigned long real;
-        unsigned long base;
+        uint32_t real;
+        uint32_t base;
       } u_nsec;
       u_nsec.real = this->data.nsec;
       *(outbuffer + offset + 0) = (u_nsec.base >> (8 * 0)) & 0xFF;
@@ -45,8 +45,8 @@
     {
       int offset = 0;
       union {
-        unsigned long real;
-        unsigned long base;
+        uint32_t real;
+        uint32_t base;
       } u_sec;
       u_sec.base = 0;
       u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 0))) << (8 * 0);
@@ -56,8 +56,8 @@
       this->data.sec = u_sec.real;
       offset += sizeof(this->data.sec);
       union {
-        unsigned long real;
-        unsigned long base;
+        uint32_t real;
+        uint32_t base;
       } u_nsec;
       u_nsec.base = 0;
       u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 0))) << (8 * 0);
--- a/std_msgs/Float32.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/Float32.h	Sun Oct 16 07:19:36 2011 +0000
@@ -19,7 +19,7 @@
       int offset = 0;
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_data;
       u_data.real = this->data;
       *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
@@ -35,7 +35,7 @@
       int offset = 0;
       union {
         float real;
-        unsigned long base;
+        uint32_t base;
       } u_data;
       u_data.base = 0;
       u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
--- a/std_msgs/Float32MultiArray.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/Float32MultiArray.h	Sun Oct 16 07:19:36 2011 +0000
@@ -7,69 +7,67 @@
 #include "../ros/msg.h"
 #include "std_msgs/MultiArrayLayout.h"
 
-namespace std_msgs
-{
+namespace std_msgs {
 
-  class Float32MultiArray : public ros::Msg
-  {
-    public:
-      std_msgs::MultiArrayLayout layout;
-      unsigned char data_length;
-      float st_data;
-      float * data;
+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;
-        unsigned long 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 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;
-        unsigned long 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 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"; };
+    virtual const char * getType() {
+        return "std_msgs/Float32MultiArray";
+    };
 
-  };
+};
 
 }
 #endif
\ No newline at end of file
--- a/std_msgs/Float64.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/Float64.h	Sun Oct 16 07:19:36 2011 +0000
@@ -12,11 +12,52 @@
   class Float64 : public ros::Msg
   {
     public:
-      float data;
+      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)
@@ -50,7 +91,7 @@
       if( ((*(inbuffer+offset++)) & 0x80) > 0) this->data = -this->data;
      return offset;
     }
-
+*/
     virtual const char * getType(){ return "std_msgs/Float64"; };
 
   };
--- a/std_msgs/Float64MultiArray.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/Float64MultiArray.h	Sun Oct 16 07:19:36 2011 +0000
@@ -7,73 +7,135 @@
 #include "../ros/msg.h"
 #include "std_msgs/MultiArrayLayout.h"
 
-namespace std_msgs
-{
+namespace std_msgs {
 
-  class Float64MultiArray : public ros::Msg
-  {
-    public:
-      std_msgs::MultiArrayLayout layout;
-      unsigned char data_length;
-      float st_data;
-      float * data;
+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++){
-      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 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;
     }
 
-    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));
+    /*
+      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;
       }
-     return offset;
-    }
 
-   virtual const char * getType(){ return "std_msgs/Float64MultiArray"; };
+      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";
+    };
 
-  };
+};
 
 }
 #endif
\ No newline at end of file
--- a/std_msgs/Header.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/Header.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_Header_h
-#define ros_Header_h
+#ifndef ros_std_msgs_Header_h
+#define ros_std_msgs_Header_h
 
 #include <stdint.h>
 #include <string.h>
@@ -105,7 +105,7 @@
      return offset;
     }
 
-    virtual const char * getType(){ return "std_msgs/Header"; };
+    const char * getType(){ return "std_msgs/Header"; };
 
   };
 
--- a/std_msgs/Int16.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/Int16.h	Sun Oct 16 07:19:36 2011 +0000
@@ -12,14 +12,14 @@
   class Int16 : public ros::Msg
   {
     public:
-      short data;
+      int16_t data;
 
     virtual int serialize(unsigned char *outbuffer)
     {
       int offset = 0;
       union {
-        short real;
-        unsigned short base;
+        int16_t;
+        uint16_t base;
       } u_data;
       u_data.real = this->data;
       *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
@@ -32,8 +32,8 @@
     {
       int offset = 0;
       union {
-        short real;
-        unsigned short base;
+        int16_t real;
+        uint16_t base;
       } u_data;
       u_data.base = 0;
       u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
--- a/std_msgs/Int16MultiArray.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/Int16MultiArray.h	Sun Oct 16 07:19:36 2011 +0000
@@ -15,8 +15,8 @@
     public:
       std_msgs::MultiArrayLayout layout;
       unsigned char data_length;
-      short st_data;
-      short * data;
+      int16_t st_data;
+      int16_t * data;
 
     virtual int serialize(unsigned char *outbuffer)
     {
@@ -28,8 +28,8 @@
       *(outbuffer + offset++) = 0;
       for( unsigned char i = 0; i < data_length; i++){
       union {
-        short real;
-        unsigned short base;
+        int16_t real;
+        uint16_t base;
       } u_datai;
       u_datai.real = this->data[i];
       *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
@@ -45,20 +45,20 @@
       offset += this->layout.deserialize(inbuffer + offset);
       unsigned char data_lengthT = *(inbuffer + offset++);
       if(data_lengthT > data_length)
-        this->data = (int*)realloc(this->data, data_lengthT * sizeof(int));
+        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 {
-        short real;
-        unsigned short base;
+        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(int));
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(int16_t));
       }
      return offset;
     }
--- a/std_msgs/Int32.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/Int32.h	Sun Oct 16 07:19:36 2011 +0000
@@ -12,14 +12,14 @@
   class Int32 : public ros::Msg
   {
     public:
-      long data;
+      int32_t data;
 
     virtual int serialize(unsigned char *outbuffer)
     {
       int offset = 0;
       union {
-        long real;
-        unsigned long base;
+        int32_t real;
+        uint32_t base;
       } u_data;
       u_data.real = this->data;
       *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
@@ -34,8 +34,8 @@
     {
       int offset = 0;
       union {
-        long real;
-        unsigned long base;
+        int32_t real;
+        uint32_t base;
       } u_data;
       u_data.base = 0;
       u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
--- a/std_msgs/Int32MultiArray.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/Int32MultiArray.h	Sun Oct 16 07:19:36 2011 +0000
@@ -15,8 +15,8 @@
     public:
       std_msgs::MultiArrayLayout layout;
       unsigned char data_length;
-      long st_data;
-      long * data;
+      int32_t st_data;
+      int32_t * data;
 
     virtual int serialize(unsigned char *outbuffer)
     {
@@ -28,8 +28,8 @@
       *(outbuffer + offset++) = 0;
       for( unsigned char i = 0; i < data_length; i++){
       union {
-        long real;
-        unsigned long base;
+        int32_t real;
+        uint32_t base;
       } u_datai;
       u_datai.real = this->data[i];
       *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
@@ -47,13 +47,13 @@
       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));
+        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 {
-        long real;
-        unsigned long base;
+        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);
@@ -62,7 +62,7 @@
       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(long));
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(int32_t));
       }
      return offset;
     }
--- a/std_msgs/Int64.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/Int64.h	Sun Oct 16 07:19:36 2011 +0000
@@ -6,43 +6,88 @@
 #include <stdlib.h>
 #include "../ros/msg.h"
 
-namespace std_msgs
-{
+namespace std_msgs {
 
-  class Int64 : public ros::Msg
-  {
-    public:
-      long data;
+class Int64 : public ros::Msg {
+public:
+    int64_t 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 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;
-      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 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 const char * getType(){ return "std_msgs/Int64"; };
+      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";
+    };
+
+};
 
 }
 #endif
\ No newline at end of file
--- a/std_msgs/Int64MultiArray.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/Int64MultiArray.h	Sun Oct 16 07:19:36 2011 +0000
@@ -7,62 +7,122 @@
 #include "../ros/msg.h"
 #include "std_msgs/MultiArrayLayout.h"
 
-namespace std_msgs
-{
+namespace std_msgs {
 
-  class Int64MultiArray : public ros::Msg
-  {
-    public:
-      std_msgs::MultiArrayLayout layout;
-      unsigned char data_length;
-      long st_data;
-      long * data;
+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++){
-      *(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 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 = (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 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 const char * getType(){ return "std_msgs/Int64MultiArray"; };
+        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";
+    };
+
+};
 
 }
 #endif
\ No newline at end of file
--- a/std_msgs/Int8.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/Int8.h	Sun Oct 16 07:19:36 2011 +0000
@@ -12,14 +12,14 @@
   class Int8 : public ros::Msg
   {
     public:
-      signed char data;
+      int8_t data;
 
     virtual int serialize(unsigned char *outbuffer)
     {
       int offset = 0;
       union {
-        signed char real;
-        unsigned char base;
+        int8_t real;
+        uint8_t base;
       } u_data;
       u_data.real = this->data;
       *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
@@ -31,8 +31,8 @@
     {
       int offset = 0;
       union {
-        signed char real;
-        unsigned char base;
+        int8_t real;
+        uint8_t base;
       } u_data;
       u_data.base = 0;
       u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
--- a/std_msgs/Int8MultiArray.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/Int8MultiArray.h	Sun Oct 16 07:19:36 2011 +0000
@@ -15,8 +15,8 @@
     public:
       std_msgs::MultiArrayLayout layout;
       unsigned char data_length;
-      signed char st_data;
-      signed char * data;
+      int8_t st_data;
+      int8_t * data;
 
     virtual int serialize(unsigned char *outbuffer)
     {
@@ -28,8 +28,8 @@
       *(outbuffer + offset++) = 0;
       for( unsigned char 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;
@@ -44,19 +44,19 @@
       offset += this->layout.deserialize(inbuffer + offset);
       unsigned char 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++){
       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);
       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;
     }
--- a/std_msgs/MultiArrayDimension.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/MultiArrayDimension.h	Sun Oct 16 07:19:36 2011 +0000
@@ -13,8 +13,8 @@
   {
     public:
       char * label;
-      unsigned long size;
-      unsigned long stride;
+      uint32_t size;
+      uint32_t stride;
 
     virtual int serialize(unsigned char *outbuffer)
     {
@@ -25,8 +25,8 @@
       memcpy(outbuffer + offset, this->label, *length_label);
       offset += *length_label;
       union {
-        unsigned long real;
-        unsigned long base;
+        uint32_t real;
+        uint32_t base;
       } u_size;
       u_size.real = this->size;
       *(outbuffer + offset + 0) = (u_size.base >> (8 * 0)) & 0xFF;
@@ -35,8 +35,8 @@
       *(outbuffer + offset + 3) = (u_size.base >> (8 * 3)) & 0xFF;
       offset += sizeof(this->size);
       union {
-        unsigned long real;
-        unsigned long base;
+        uint32_t real;
+        uint32_t base;
       } u_stride;
       u_stride.real = this->stride;
       *(outbuffer + offset + 0) = (u_stride.base >> (8 * 0)) & 0xFF;
@@ -59,8 +59,8 @@
       this->label = (char *)(inbuffer + offset-1);
       offset += length_label;
       union {
-        unsigned long real;
-        unsigned long base;
+        uint32_t real;
+        uint32_t base;
       } u_size;
       u_size.base = 0;
       u_size.base |= ((typeof(u_size.base)) (*(inbuffer + offset + 0))) << (8 * 0);
@@ -70,8 +70,8 @@
       this->size = u_size.real;
       offset += sizeof(this->size);
       union {
-        unsigned long real;
-        unsigned long base;
+        uint32_t real;
+        uint32_t base;
       } u_stride;
       u_stride.base = 0;
       u_stride.base |= ((typeof(u_stride.base)) (*(inbuffer + offset + 0))) << (8 * 0);
--- a/std_msgs/MultiArrayLayout.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/MultiArrayLayout.h	Sun Oct 16 07:19:36 2011 +0000
@@ -7,69 +7,67 @@
 #include "../ros/msg.h"
 #include "std_msgs/MultiArrayDimension.h"
 
-namespace std_msgs
-{
+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;
+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 {
-        unsigned long real;
-        unsigned long 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 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 {
-        unsigned long real;
-        unsigned long 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 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"; };
+    virtual const char * getType() {
+        return "std_msgs/MultiArrayLayout";
+    };
 
-  };
+};
 
 }
 #endif
\ No newline at end of file
--- a/std_msgs/Time.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/Time.h	Sun Oct 16 07:19:36 2011 +0000
@@ -1,5 +1,5 @@
-#ifndef ros_Time_h
-#define ros_Time_h
+#ifndef ros_std_msgs_Time_h
+#define ros_std_msgs_Time_h
 
 #include <stdint.h>
 #include <string.h>
@@ -19,8 +19,8 @@
     {
       int offset = 0;
       union {
-        unsigned long real;
-        unsigned long base;
+        uint32_t real;
+        uint32_t base;
       } u_sec;
       u_sec.real = this->data.sec;
       *(outbuffer + offset + 0) = (u_sec.base >> (8 * 0)) & 0xFF;
@@ -29,8 +29,8 @@
       *(outbuffer + offset + 3) = (u_sec.base >> (8 * 3)) & 0xFF;
       offset += sizeof(this->data.sec);
       union {
-        unsigned long real;
-        unsigned long base;
+        uint32_t real;
+        uint32_t base;
       } u_nsec;
       u_nsec.real = this->data.nsec;
       *(outbuffer + offset + 0) = (u_nsec.base >> (8 * 0)) & 0xFF;
@@ -45,8 +45,8 @@
     {
       int offset = 0;
       union {
-        unsigned long real;
-        unsigned long base;
+        uint32_t real;
+        uint32_t base;
       } u_sec;
       u_sec.base = 0;
       u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 0))) << (8 * 0);
@@ -56,8 +56,8 @@
       this->data.sec = u_sec.real;
       offset += sizeof(this->data.sec);
       union {
-        unsigned long real;
-        unsigned long base;
+        uint32_t real;
+        uint32_t base;
       } u_nsec;
       u_nsec.base = 0;
       u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 0))) << (8 * 0);
--- a/std_msgs/UInt16.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/UInt16.h	Sun Oct 16 07:19:36 2011 +0000
@@ -12,14 +12,14 @@
   class UInt16 : public ros::Msg
   {
     public:
-      unsigned short data;
+      uint16_t data;
 
     virtual int serialize(unsigned char *outbuffer)
     {
       int offset = 0;
       union {
-        unsigned short real;
-        unsigned short base;
+        uint16_t real;
+        uint16_t base;
       } u_data;
       u_data.real = this->data;
       *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
@@ -32,8 +32,8 @@
     {
       int offset = 0;
       union {
-        unsigned short real;
-        unsigned short base;
+        uint16_t real;
+        uint16_t base;
       } u_data;
       u_data.base = 0;
       u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
--- a/std_msgs/UInt16MultiArray.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/UInt16MultiArray.h	Sun Oct 16 07:19:36 2011 +0000
@@ -15,8 +15,8 @@
     public:
       std_msgs::MultiArrayLayout layout;
       unsigned char data_length;
-      unsigned short st_data;
-      unsigned short * data;
+      uint16_t st_data;
+      uint16_t * data;
 
     virtual int serialize(unsigned char *outbuffer)
     {
@@ -28,8 +28,8 @@
       *(outbuffer + offset++) = 0;
       for( unsigned char i = 0; i < data_length; i++){
       union {
-        unsigned short real;
-        unsigned short base;
+        uint16_t real;
+        uint16_t base;
       } u_datai;
       u_datai.real = this->data[i];
       *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
@@ -45,20 +45,20 @@
       offset += this->layout.deserialize(inbuffer + offset);
       unsigned char data_lengthT = *(inbuffer + offset++);
       if(data_lengthT > data_length)
-        this->data = (unsigned int*)realloc(this->data, data_lengthT * sizeof(unsigned int));
+        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 {
-        unsigned short real;
-        unsigned short base;
+        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(unsigned int));
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(uint16_t));
       }
      return offset;
     }
--- a/std_msgs/UInt32.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/UInt32.h	Sun Oct 16 07:19:36 2011 +0000
@@ -12,14 +12,14 @@
   class UInt32 : public ros::Msg
   {
     public:
-      unsigned long data;
+      uint32_t data;
 
     virtual int serialize(unsigned char *outbuffer)
     {
       int offset = 0;
       union {
-        unsigned long real;
-        unsigned long base;
+        uint32_t real;
+        uint32_t base;
       } u_data;
       u_data.real = this->data;
       *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
@@ -34,8 +34,8 @@
     {
       int offset = 0;
       union {
-        unsigned long real;
-        unsigned long base;
+        uint32_t real;
+        uint32_t base;
       } u_data;
       u_data.base = 0;
       u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
--- a/std_msgs/UInt32MultiArray.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/UInt32MultiArray.h	Sun Oct 16 07:19:36 2011 +0000
@@ -15,8 +15,8 @@
     public:
       std_msgs::MultiArrayLayout layout;
       unsigned char data_length;
-      unsigned long st_data;
-      unsigned long * data;
+      uint32_t st_data;
+      uint32_t * data;
 
     virtual int serialize(unsigned char *outbuffer)
     {
@@ -28,8 +28,8 @@
       *(outbuffer + offset++) = 0;
       for( unsigned char i = 0; i < data_length; i++){
       union {
-        unsigned long real;
-        unsigned long base;
+        uint32_t real;
+        uint32_t base;
       } u_datai;
       u_datai.real = this->data[i];
       *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
@@ -47,13 +47,13 @@
       offset += this->layout.deserialize(inbuffer + offset);
       unsigned char data_lengthT = *(inbuffer + offset++);
       if(data_lengthT > data_length)
-        this->data = (unsigned long*)realloc(this->data, data_lengthT * sizeof(unsigned long));
+        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 {
-        unsigned long real;
-        unsigned long base;
+        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);
@@ -62,7 +62,7 @@
       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(unsigned long));
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(uint32_t));
       }
      return offset;
     }
--- a/std_msgs/UInt64.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/UInt64.h	Sun Oct 16 07:19:36 2011 +0000
@@ -6,43 +6,86 @@
 #include <stdlib.h>
 #include "../ros/msg.h"
 
-namespace std_msgs
-{
+namespace std_msgs {
 
-  class UInt64 : public ros::Msg
-  {
-    public:
-      long data;
+class UInt64 : public ros::Msg {
+public:
+    uint64_t 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 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;
-      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 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"; };
+    /*
+      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";
+    };
+
+};
 
 }
 #endif
\ No newline at end of file
--- a/std_msgs/UInt64MultiArray.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/UInt64MultiArray.h	Sun Oct 16 07:19:36 2011 +0000
@@ -7,62 +7,123 @@
 #include "../ros/msg.h"
 #include "std_msgs/MultiArrayLayout.h"
 
-namespace std_msgs
-{
+namespace std_msgs {
 
-  class UInt64MultiArray : public ros::Msg
-  {
-    public:
-      std_msgs::MultiArrayLayout layout;
-      unsigned char data_length;
-      long st_data;
-      long * data;
+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++){
-      *(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 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 = (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));
+    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;
       }
-     return offset;
-    }
 
-   virtual const char * getType(){ return "std_msgs/UInt64MultiArray"; };
+      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";
+    };
 
-  };
+};
 
 }
 #endif
\ No newline at end of file
--- a/std_msgs/UInt8.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/UInt8.h	Sun Oct 16 07:19:36 2011 +0000
@@ -12,14 +12,14 @@
   class UInt8 : public ros::Msg
   {
     public:
-      unsigned char data;
+      uint8_t data;
 
     virtual int serialize(unsigned char *outbuffer)
     {
       int offset = 0;
       union {
-        unsigned char real;
-        unsigned char base;
+        uint8_t real;
+        uint8_t base;
       } u_data;
       u_data.real = this->data;
       *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
@@ -31,8 +31,8 @@
     {
       int offset = 0;
       union {
-        unsigned char real;
-        unsigned char base;
+        uint8_t real;
+        uint8_t base;
       } u_data;
       u_data.base = 0;
       u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
--- a/std_msgs/UInt8MultiArray.h	Fri Aug 19 09:06:30 2011 +0000
+++ b/std_msgs/UInt8MultiArray.h	Sun Oct 16 07:19:36 2011 +0000
@@ -15,8 +15,8 @@
     public:
       std_msgs::MultiArrayLayout layout;
       unsigned char data_length;
-      unsigned char st_data;
-      unsigned char * data;
+      uint8_t st_data;
+      uint8_t * data;
 
     virtual int serialize(unsigned char *outbuffer)
     {
@@ -28,8 +28,8 @@
       *(outbuffer + offset++) = 0;
       for( unsigned char i = 0; i < data_length; i++){
       union {
-        unsigned char real;
-        unsigned char base;
+        uint8_t real;
+        uint8_t base;
       } u_datai;
       u_datai.real = this->data[i];
       *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
@@ -44,19 +44,19 @@
       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));
+        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;
+        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));
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t));
       }
      return offset;
     }