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:
Fri Aug 19 09:06:30 2011 +0000
Child:
1:ff0ec969dad1
Commit message:

Changed in this revision

MbedHardware.h Show annotated file Show diff for this revision Revisions of this file
dianostic_msgs/DiagnosticArray.h Show annotated file Show diff for this revision Revisions of this file
dianostic_msgs/DiagnosticStatus.h Show annotated file Show diff for this revision Revisions of this file
dianostic_msgs/KeyValue.h Show annotated file Show diff for this revision Revisions of this file
dianostic_msgs/SelfTest.h Show annotated file Show diff for this revision Revisions of this file
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
nav_msgs/GetMap.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/GetPlan.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/GridCells.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/MapMetaData.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/OccupancyGrid.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/Odometry.h Show annotated file Show diff for this revision Revisions of this file
nav_msgs/Path.h Show annotated file Show diff for this revision Revisions of this file
ros.h Show annotated file Show diff for this revision Revisions of this file
ros/duration.h Show annotated file Show diff for this revision Revisions of this file
ros/msg.h Show annotated file Show diff for this revision Revisions of this file
ros/msg_receiver.h Show 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 annotated file 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_mbed/Adc.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/RequestParam.h Show annotated file Show diff for this revision Revisions of this file
rosserial_msgs/TopicInfo.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/CameraInfo.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/ChannelFloat32.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/CompressedImage.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/Image.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/Imu.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/JointState.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/LaserScan.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/NavSatFix.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/NavSatStatus.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/PointCloud.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/PointCloud2.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/PointField.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/Range.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/RegionOfInterest.h Show annotated file Show diff for this revision Revisions of this file
sensor_msgs/SetCameraInfo.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Bool.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Byte.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/ByteMultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Char.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/ColorRGBA.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Duration.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Empty.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Float32.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Float32MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Float64.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Float64MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Header.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Int16.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Int16MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Int32.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Int32MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Int64.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Int64MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Int8.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Int8MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/MultiArrayDimension.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/MultiArrayLayout.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/String.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/Time.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/UInt16.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/UInt16MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/UInt32.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/UInt32MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/UInt64.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/UInt64MultiArray.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/UInt8.h Show annotated file Show diff for this revision Revisions of this file
std_msgs/UInt8MultiArray.h Show annotated file Show diff for this revision Revisions of this file
tf/FrameGraph.h Show annotated file Show diff for this revision Revisions of this file
tf/tfMessage.h Show annotated file Show diff for this revision Revisions of this file
tf/transform_broadcaster.h Show annotated file Show diff for this revision Revisions of this file
time.cpp Show annotated file Show diff for this revision Revisions of this file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MbedHardware.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,66 @@
+/*
+ * mbedHardware
+ *
+ *  Created on: Aug 17, 2011
+ *      Author: nucho
+ */
+
+#ifndef MBEDHARDWARE_H_
+#define MBEDHARDWARE_H_
+
+#include"mbed.h"
+
+class MbedHardware {
+public:
+    MbedHardware(Serial* io , long baud= 57600)
+            :iostream(*io){
+        baud_ = baud;
+        t.start();
+    }
+    MbedHardware()
+            :iostream(USBTX, USBRX) {
+        baud_ = 57600;
+        t.start();
+    }
+    MbedHardware(MbedHardware& h)
+            :iostream(h.iostream) {
+        this->baud_ = h.baud_;
+        
+        t.start();
+    }
+
+    void setBaud(long baud) {
+        this->baud_= baud;
+    }
+
+    int getBaud() {
+        return baud_;
+    }
+
+    void init() {
+        iostream.baud(baud_);
+    }
+
+    int read() {
+        if (iostream.readable()) {
+            return iostream.getc();
+        } else {
+            return -1;
+        }
+    };
+    void write(uint8_t* data, int length) {
+        for (int i=0; i<length; i++) iostream.putc(data[i]);
+    }
+
+    unsigned long time() {
+        return t.read_ms();
+    }
+
+protected:
+    long baud_;
+    Serial iostream;
+    Timer t;
+};
+
+
+#endif /* MBEDHARDWARE_H_ */
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/dianostic_msgs/DiagnosticArray.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,57 @@
+#ifndef ros_DiagnosticArray_h
+#define ros_DiagnosticArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/Header.h"
+#include "diagnostic_msgs/DiagnosticStatus.h"
+
+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;
+
+    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 const char * getType(){ return "diagnostic_msgs/DiagnosticArray"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/dianostic_msgs/DiagnosticStatus.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,114 @@
+#ifndef ros_DiagnosticStatus_h
+#define ros_DiagnosticStatus_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "diagnostic_msgs/KeyValue.h"
+
+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 };
+
+    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 const char * getType(){ return "diagnostic_msgs/DiagnosticStatus"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/dianostic_msgs/KeyValue.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,61 @@
+#ifndef ros_KeyValue_h
+#define ros_KeyValue_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace diagnostic_msgs
+{
+
+  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 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"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/dianostic_msgs/SelfTest.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,104 @@
+#ifndef ros_SERVICE_SelfTest_h
+#define ros_SERVICE_SelfTest_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "diagnostic_msgs/DiagnosticStatus.h"
+
+namespace diagnostic_msgs
+{
+
+static const char SELFTEST[] = "diagnostic_msgs/SelfTest";
+
+  class SelfTestRequest : public ros::Msg
+  {
+    public:
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return SELFTEST; };
+
+  };
+
+  class SelfTestResponse : public ros::Msg
+  {
+    public:
+      char * id;
+      unsigned char passed;
+      unsigned char status_length;
+      diagnostic_msgs::DiagnosticStatus st_status;
+      diagnostic_msgs::DiagnosticStatus * status;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      long * length_id = (long *)(outbuffer + offset);
+      *length_id = strlen( (const char*) this->id);
+      offset += 4;
+      memcpy(outbuffer + offset, this->id, *length_id);
+      offset += *length_id;
+      union {
+        unsigned char real;
+        unsigned char base;
+      } u_passed;
+      u_passed.real = this->passed;
+      *(outbuffer + offset + 0) = (u_passed.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->passed);
+      *(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;
+      uint32_t length_id = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_id; ++k){
+          inbuffer[k-1]=inbuffer[k];
+           }
+      inbuffer[offset+length_id-1]=0;
+      this->id = (char *)(inbuffer + offset-1);
+      offset += length_id;
+      union {
+        unsigned char real;
+        unsigned char base;
+      } u_passed;
+      u_passed.base = 0;
+      u_passed.base |= ((typeof(u_passed.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->passed = u_passed.real;
+      offset += sizeof(this->passed);
+      unsigned char status_lengthT = *(inbuffer + offset++);
+      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 SELFTEST; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/duration.cpp	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,86 @@
+/* 
+ * 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
+ */
+
+#include "ros/duration.h"
+#include <math.h>
+
+
+namespace ros
+{
+  void normalizeSecNSecSigned(long &sec, long &nsec)
+  {
+    long nsec_part = nsec;
+    long sec_part = sec;
+     
+    while (nsec_part > 1000000000L)
+    {
+      nsec_part -= 1000000000L;
+      ++sec_part;
+    }
+    while (nsec_part < 0)
+    {
+      nsec_part += 1000000000L;
+      --sec_part;
+    }
+    sec = sec_part;
+    nsec = nsec_part;
+  }
+
+  Duration& Duration::operator+=(const Duration &rhs)
+  {
+    sec += rhs.sec;
+    nsec += rhs.nsec;
+    normalizeSecNSecSigned(sec, nsec);
+    return *this;
+  }
+
+  Duration& Duration::operator-=(const Duration &rhs){
+    sec += -rhs.sec;
+    nsec += -rhs.nsec;
+    normalizeSecNSecSigned(sec, nsec);
+    return *this;
+  }
+
+  Duration& Duration::operator*=(double scale){
+    sec *= scale;
+    nsec *= scale;
+    normalizeSecNSecSigned(sec, nsec);
+    return *this;
+  }
+
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Point.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,111 @@
+#ifndef ros_Point_h
+#define ros_Point_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace geometry_msgs
+{
+
+  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 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"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Point32.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,99 @@
+#ifndef ros_Point32_h
+#define ros_Point32_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace geometry_msgs
+{
+
+  class Point32 : public ros::Msg
+  {
+    public:
+      float x;
+      float y;
+      float z;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      union {
+        float real;
+        unsigned long base;
+      } u_x;
+      u_x.real = this->x;
+      *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->x);
+      union {
+        float real;
+        unsigned long base;
+      } u_y;
+      u_y.real = this->y;
+      *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->y);
+      union {
+        float real;
+        unsigned long base;
+      } u_z;
+      u_z.real = this->z;
+      *(outbuffer + offset + 0) = (u_z.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_z.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_z.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_z.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->z);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        float real;
+        unsigned long base;
+      } u_x;
+      u_x.base = 0;
+      u_x.base |= ((typeof(u_x.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_x.base |= ((typeof(u_x.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_x.base |= ((typeof(u_x.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_x.base |= ((typeof(u_x.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->x = u_x.real;
+      offset += sizeof(this->x);
+      union {
+        float real;
+        unsigned long base;
+      } u_y;
+      u_y.base = 0;
+      u_y.base |= ((typeof(u_y.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_y.base |= ((typeof(u_y.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_y.base |= ((typeof(u_y.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_y.base |= ((typeof(u_y.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->y = u_y.real;
+      offset += sizeof(this->y);
+      union {
+        float real;
+        unsigned long base;
+      } u_z;
+      u_z.base = 0;
+      u_z.base |= ((typeof(u_z.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_z.base |= ((typeof(u_z.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_z.base |= ((typeof(u_z.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_z.base |= ((typeof(u_z.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->z = u_z.real;
+      offset += sizeof(this->z);
+     return offset;
+    }
+
+    virtual const char * getType(){ return "geometry_msgs/Point32"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/PointStamped.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,41 @@
+#ifndef ros_PointStamped_h
+#define ros_PointStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Point.h"
+
+namespace geometry_msgs
+{
+
+  class PointStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      geometry_msgs::Point point;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->point.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->point.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    virtual const char * getType(){ return "geometry_msgs/PointStamped"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Polygon.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,53 @@
+#ifndef ros_Polygon_h
+#define ros_Polygon_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "geometry_msgs/Point32.h"
+
+namespace geometry_msgs
+{
+
+  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 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"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/PolygonStamped.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,41 @@
+#ifndef ros_PolygonStamped_h
+#define ros_PolygonStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Polygon.h"
+
+namespace geometry_msgs
+{
+
+  class PolygonStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      geometry_msgs::Polygon polygon;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->polygon.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->polygon.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "geometry_msgs/PolygonStamped"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Pose.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,41 @@
+#ifndef ros_Pose_h
+#define ros_Pose_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "geometry_msgs/Point.h"
+#include "geometry_msgs/Quaternion.h"
+
+namespace geometry_msgs
+{
+
+  class Pose : public ros::Msg
+  {
+    public:
+      geometry_msgs::Point position;
+      geometry_msgs::Quaternion orientation;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->position.serialize(outbuffer + offset);
+      offset += this->orientation.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->position.deserialize(inbuffer + offset);
+      offset += this->orientation.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+   virtual virtual const char * getType(){ return "geometry_msgs/Pose"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Pose2D.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,111 @@
+#ifndef ros_Pose2D_h
+#define ros_Pose2D_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace geometry_msgs
+{
+
+  class Pose2D : public ros::Msg
+  {
+    public:
+      float x;
+      float y;
+      float theta;
+
+    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_theta = (long *) &(this->theta);
+      long exp_theta = (((*val_theta)>>23)&255);
+      if(exp_theta != 0)
+        exp_theta += 1023-127;
+      long sig_theta = *val_theta;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = (sig_theta<<5) & 0xff;
+      *(outbuffer + offset++) = (sig_theta>>3) & 0xff;
+      *(outbuffer + offset++) = (sig_theta>>11) & 0xff;
+      *(outbuffer + offset++) = ((exp_theta<<4) & 0xF0) | ((sig_theta>>19)&0x0F);
+      *(outbuffer + offset++) = (exp_theta>>4) & 0x7F;
+      if(this->theta < 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_theta = (unsigned long*) &(this->theta);
+      offset += 3;
+      *val_theta = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_theta |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_theta |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_theta |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
+      unsigned long exp_theta = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_theta |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      if(exp_theta !=0)
+        *val_theta |= ((exp_theta)-1023+127)<<23;
+      if( ((*(inbuffer+offset++)) & 0x80) > 0) this->theta = -this->theta;
+     return offset;
+    }
+
+   virtual const char * getType(){ return "geometry_msgs/Pose2D"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/PoseArray.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,57 @@
+#ifndef ros_PoseArray_h
+#define ros_PoseArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Pose.h"
+
+namespace geometry_msgs
+{
+
+  class PoseArray : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      unsigned char poses_length;
+      geometry_msgs::Pose st_poses;
+      geometry_msgs::Pose * poses;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = poses_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( unsigned char i = 0; i < poses_length; i++){
+      offset += this->poses[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      unsigned char poses_lengthT = *(inbuffer + offset++);
+      if(poses_lengthT > poses_length)
+        this->poses = (geometry_msgs::Pose*)realloc(this->poses, poses_lengthT * sizeof(geometry_msgs::Pose));
+      offset += 3;
+      poses_length = poses_lengthT;
+      for( unsigned char i = 0; i < poses_length; i++){
+      offset += this->st_poses.deserialize(inbuffer + offset);
+        memcpy( &(this->poses[i]), &(this->st_poses), sizeof(geometry_msgs::Pose));
+      }
+     return offset;
+    }
+
+    virtual const char * getType(){ return "geometry_msgs/PoseArray"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/PoseStamped.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,41 @@
+#ifndef ros_PoseStamped_h
+#define ros_PoseStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Pose.h"
+
+namespace geometry_msgs
+{
+
+  class PoseStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      geometry_msgs::Pose pose;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->pose.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->pose.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "geometry_msgs/PoseStamped"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/PoseWithCovariance.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,69 @@
+#ifndef ros_PoseWithCovariance_h
+#define ros_PoseWithCovariance_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "geometry_msgs/Pose.h"
+
+namespace geometry_msgs
+{
+
+  class PoseWithCovariance : public ros::Msg
+  {
+    public:
+      geometry_msgs::Pose pose;
+      float covariance[36];
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->pose.serialize(outbuffer + offset);
+      unsigned char * covariance_val = (unsigned char *) this->covariance;
+      for( unsigned char i = 0; i < 36; i++){
+      long * val_covariancei = (long *) &(this->covariance[i]);
+      long exp_covariancei = (((*val_covariancei)>>23)&255);
+      if(exp_covariancei != 0)
+        exp_covariancei += 1023-127;
+      long sig_covariancei = *val_covariancei;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = (sig_covariancei<<5) & 0xff;
+      *(outbuffer + offset++) = (sig_covariancei>>3) & 0xff;
+      *(outbuffer + offset++) = (sig_covariancei>>11) & 0xff;
+      *(outbuffer + offset++) = ((exp_covariancei<<4) & 0xF0) | ((sig_covariancei>>19)&0x0F);
+      *(outbuffer + offset++) = (exp_covariancei>>4) & 0x7F;
+      if(this->covariance[i] < 0) *(outbuffer + offset -1) |= 0x80;
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->pose.deserialize(inbuffer + offset);
+      unsigned char * covariance_val = (unsigned char *) this->covariance;
+      for( unsigned char i = 0; i < 36; i++){
+      unsigned long * val_covariancei = (unsigned long*) &(this->covariance[i]);
+      offset += 3;
+      *val_covariancei = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
+      unsigned long exp_covariancei = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      if(exp_covariancei !=0)
+        *val_covariancei |= ((exp_covariancei)-1023+127)<<23;
+      if( ((*(inbuffer+offset++)) & 0x80) > 0) this->covariance[i] = -this->covariance[i];
+      }
+     return offset;
+    }
+
+   virtual const char * getType(){ return "geometry_msgs/PoseWithCovariance"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/PoseWithCovarianceStamped.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,41 @@
+#ifndef ros_PoseWithCovarianceStamped_h
+#define ros_PoseWithCovarianceStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/PoseWithCovariance.h"
+
+namespace geometry_msgs
+{
+
+  class PoseWithCovarianceStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      geometry_msgs::PoseWithCovariance pose;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->pose.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->pose.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "geometry_msgs/PoseWithCovarianceStamped"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Quaternion.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,137 @@
+#ifndef ros_Quaternion_h
+#define ros_Quaternion_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace geometry_msgs
+{
+
+  class Quaternion : public ros::Msg
+  {
+    public:
+      float x;
+      float y;
+      float z;
+      float w;
+
+    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;
+      long * val_w = (long *) &(this->w);
+      long exp_w = (((*val_w)>>23)&255);
+      if(exp_w != 0)
+        exp_w += 1023-127;
+      long sig_w = *val_w;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = (sig_w<<5) & 0xff;
+      *(outbuffer + offset++) = (sig_w>>3) & 0xff;
+      *(outbuffer + offset++) = (sig_w>>11) & 0xff;
+      *(outbuffer + offset++) = ((exp_w<<4) & 0xF0) | ((sig_w>>19)&0x0F);
+      *(outbuffer + offset++) = (exp_w>>4) & 0x7F;
+      if(this->w < 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;
+      unsigned long * val_w = (unsigned long*) &(this->w);
+      offset += 3;
+      *val_w = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_w |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_w |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_w |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
+      unsigned long exp_w = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_w |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      if(exp_w !=0)
+        *val_w |= ((exp_w)-1023+127)<<23;
+      if( ((*(inbuffer+offset++)) & 0x80) > 0) this->w = -this->w;
+     return offset;
+    }
+
+    virtual const char * getType(){ return "geometry_msgs/Quaternion"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/QuaternionStamped.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,41 @@
+#ifndef ros_QuaternionStamped_h
+#define ros_QuaternionStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Quaternion.h"
+
+namespace geometry_msgs
+{
+
+  class QuaternionStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      geometry_msgs::Quaternion quaternion;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->quaternion.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->quaternion.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "geometry_msgs/QuaternionStamped"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Transform.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,41 @@
+#ifndef ros_Transform_h
+#define ros_Transform_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "geometry_msgs/Vector3.h"
+#include "geometry_msgs/Quaternion.h"
+
+namespace geometry_msgs
+{
+
+  class Transform : public ros::Msg
+  {
+    public:
+      geometry_msgs::Vector3 translation;
+      geometry_msgs::Quaternion rotation;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->translation.serialize(outbuffer + offset);
+      offset += this->rotation.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->translation.deserialize(inbuffer + offset);
+      offset += this->rotation.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    virtual const char * getType(){ return "geometry_msgs/Transform"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/TransformStamped.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,55 @@
+#ifndef ros_TransformStamped_h
+#define ros_TransformStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Transform.h"
+
+namespace geometry_msgs
+{
+
+  class TransformStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      char * child_frame_id;
+      geometry_msgs::Transform transform;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      long * length_child_frame_id = (long *)(outbuffer + offset);
+      *length_child_frame_id = strlen( (const char*) this->child_frame_id);
+      offset += 4;
+      memcpy(outbuffer + offset, this->child_frame_id, *length_child_frame_id);
+      offset += *length_child_frame_id;
+      offset += this->transform.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint32_t length_child_frame_id = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_child_frame_id; ++k){
+          inbuffer[k-1]=inbuffer[k];
+           }
+      inbuffer[offset+length_child_frame_id-1]=0;
+      this->child_frame_id = (char *)(inbuffer + offset-1);
+      offset += length_child_frame_id;
+      offset += this->transform.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+    virtual const char * getType(){ return "geometry_msgs/TransformStamped"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Twist.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,40 @@
+#ifndef ros_Twist_h
+#define ros_Twist_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "geometry_msgs/Vector3.h"
+
+namespace geometry_msgs
+{
+
+  class Twist : public ros::Msg
+  {
+    public:
+      geometry_msgs::Vector3 linear;
+      geometry_msgs::Vector3 angular;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->linear.serialize(outbuffer + offset);
+      offset += this->angular.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->linear.deserialize(inbuffer + offset);
+      offset += this->angular.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "geometry_msgs/Twist"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/TwistStamped.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,41 @@
+#ifndef ros_TwistStamped_h
+#define ros_TwistStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Twist.h"
+
+namespace geometry_msgs
+{
+
+  class TwistStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      geometry_msgs::Twist twist;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->twist.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->twist.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "geometry_msgs/TwistStamped"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/TwistWithCovariance.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,69 @@
+#ifndef ros_TwistWithCovariance_h
+#define ros_TwistWithCovariance_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "geometry_msgs/Twist.h"
+
+namespace geometry_msgs
+{
+
+  class TwistWithCovariance : public ros::Msg
+  {
+    public:
+      geometry_msgs::Twist twist;
+      float covariance[36];
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->twist.serialize(outbuffer + offset);
+      unsigned char * covariance_val = (unsigned char *) this->covariance;
+      for( unsigned char i = 0; i < 36; i++){
+      long * val_covariancei = (long *) &(this->covariance[i]);
+      long exp_covariancei = (((*val_covariancei)>>23)&255);
+      if(exp_covariancei != 0)
+        exp_covariancei += 1023-127;
+      long sig_covariancei = *val_covariancei;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = (sig_covariancei<<5) & 0xff;
+      *(outbuffer + offset++) = (sig_covariancei>>3) & 0xff;
+      *(outbuffer + offset++) = (sig_covariancei>>11) & 0xff;
+      *(outbuffer + offset++) = ((exp_covariancei<<4) & 0xF0) | ((sig_covariancei>>19)&0x0F);
+      *(outbuffer + offset++) = (exp_covariancei>>4) & 0x7F;
+      if(this->covariance[i] < 0) *(outbuffer + offset -1) |= 0x80;
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->twist.deserialize(inbuffer + offset);
+      unsigned char * covariance_val = (unsigned char *) this->covariance;
+      for( unsigned char i = 0; i < 36; i++){
+      unsigned long * val_covariancei = (unsigned long*) &(this->covariance[i]);
+      offset += 3;
+      *val_covariancei = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
+      unsigned long exp_covariancei = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      if(exp_covariancei !=0)
+        *val_covariancei |= ((exp_covariancei)-1023+127)<<23;
+      if( ((*(inbuffer+offset++)) & 0x80) > 0) this->covariance[i] = -this->covariance[i];
+      }
+     return offset;
+    }
+
+   virtual const char * getType(){ return "geometry_msgs/TwistWithCovariance"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/TwistWithCovarianceStamped.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,41 @@
+#ifndef ros_TwistWithCovarianceStamped_h
+#define ros_TwistWithCovarianceStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/TwistWithCovariance.h"
+
+namespace geometry_msgs
+{
+
+  class TwistWithCovarianceStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      geometry_msgs::TwistWithCovariance twist;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->twist.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->twist.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "geometry_msgs/TwistWithCovarianceStamped"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Vector3.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,111 @@
+#ifndef ros_Vector3_h
+#define ros_Vector3_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace geometry_msgs
+{
+
+  class Vector3 : 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 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/Vector3"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Vector3Stamped.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,41 @@
+#ifndef ros_Vector3Stamped_h
+#define ros_Vector3Stamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Vector3.h"
+
+namespace geometry_msgs
+{
+
+  class Vector3Stamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      geometry_msgs::Vector3 vector;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->vector.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->vector.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "geometry_msgs/Vector3Stamped"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/Wrench.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,40 @@
+#ifndef ros_Wrench_h
+#define ros_Wrench_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "geometry_msgs/Vector3.h"
+
+namespace geometry_msgs
+{
+
+  class Wrench : public ros::Msg
+  {
+    public:
+      geometry_msgs::Vector3 force;
+      geometry_msgs::Vector3 torque;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->force.serialize(outbuffer + offset);
+      offset += this->torque.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->force.deserialize(inbuffer + offset);
+      offset += this->torque.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "geometry_msgs/Wrench"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/geometry_msgs/WrenchStamped.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,41 @@
+#ifndef ros_WrenchStamped_h
+#define ros_WrenchStamped_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Wrench.h"
+
+namespace geometry_msgs
+{
+
+  class WrenchStamped : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      geometry_msgs::Wrench wrench;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->wrench.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->wrench.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "geometry_msgs/WrenchStamped"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/GetMap.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,58 @@
+#ifndef ros_SERVICE_GetMap_h
+#define ros_SERVICE_GetMap_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "nav_msgs/OccupancyGrid.h"
+
+namespace nav_msgs
+{
+
+static const char GETMAP[] = "nav_msgs/GetMap";
+
+  class GetMapRequest : public ros::Msg
+  {
+    public:
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return GETMAP; };
+
+  };
+
+  class GetMapResponse : public ros::Msg
+  {
+    public:
+      nav_msgs::OccupancyGrid map;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->map.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->map.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+   virtual const char * getType(){ return GETMAP; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/GetPlan.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,87 @@
+#ifndef ros_SERVICE_GetPlan_h
+#define ros_SERVICE_GetPlan_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "geometry_msgs/PoseStamped.h"
+#include "nav_msgs/Path.h"
+
+namespace nav_msgs
+{
+
+static const char GETPLAN[] = "nav_msgs/GetPlan";
+
+  class GetPlanRequest : public ros::Msg
+  {
+    public:
+      geometry_msgs::PoseStamped start;
+      geometry_msgs::PoseStamped goal;
+      float tolerance;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->start.serialize(outbuffer + offset);
+      offset += this->goal.serialize(outbuffer + offset);
+      union {
+        float real;
+        unsigned long base;
+      } u_tolerance;
+      u_tolerance.real = this->tolerance;
+      *(outbuffer + offset + 0) = (u_tolerance.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_tolerance.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_tolerance.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_tolerance.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->tolerance);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->start.deserialize(inbuffer + offset);
+      offset += this->goal.deserialize(inbuffer + offset);
+      union {
+        float real;
+        unsigned long base;
+      } u_tolerance;
+      u_tolerance.base = 0;
+      u_tolerance.base |= ((typeof(u_tolerance.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_tolerance.base |= ((typeof(u_tolerance.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_tolerance.base |= ((typeof(u_tolerance.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_tolerance.base |= ((typeof(u_tolerance.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->tolerance = u_tolerance.real;
+      offset += sizeof(this->tolerance);
+     return offset;
+    }
+
+    const char * getType(){ return GETPLAN; };
+
+  };
+
+  class GetPlanResponse : public ros::Msg
+  {
+    public:
+      nav_msgs::Path plan;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->plan.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->plan.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+   virtual const char * getType(){ return GETPLAN; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/GridCells.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,101 @@
+#ifndef ros_GridCells_h
+#define ros_GridCells_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Point.h"
+
+namespace nav_msgs
+{
+
+  class GridCells : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      float cell_width;
+      float cell_height;
+      unsigned char cells_length;
+      geometry_msgs::Point st_cells;
+      geometry_msgs::Point * cells;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      union {
+        float real;
+        unsigned long base;
+      } u_cell_width;
+      u_cell_width.real = this->cell_width;
+      *(outbuffer + offset + 0) = (u_cell_width.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_cell_width.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_cell_width.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_cell_width.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->cell_width);
+      union {
+        float real;
+        unsigned long base;
+      } u_cell_height;
+      u_cell_height.real = this->cell_height;
+      *(outbuffer + offset + 0) = (u_cell_height.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_cell_height.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_cell_height.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_cell_height.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->cell_height);
+      *(outbuffer + offset++) = cells_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( unsigned char i = 0; i < cells_length; i++){
+      offset += this->cells[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      union {
+        float real;
+        unsigned long base;
+      } u_cell_width;
+      u_cell_width.base = 0;
+      u_cell_width.base |= ((typeof(u_cell_width.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_cell_width.base |= ((typeof(u_cell_width.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_cell_width.base |= ((typeof(u_cell_width.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_cell_width.base |= ((typeof(u_cell_width.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->cell_width = u_cell_width.real;
+      offset += sizeof(this->cell_width);
+      union {
+        float real;
+        unsigned long base;
+      } u_cell_height;
+      u_cell_height.base = 0;
+      u_cell_height.base |= ((typeof(u_cell_height.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_cell_height.base |= ((typeof(u_cell_height.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_cell_height.base |= ((typeof(u_cell_height.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_cell_height.base |= ((typeof(u_cell_height.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->cell_height = u_cell_height.real;
+      offset += sizeof(this->cell_height);
+      unsigned char cells_lengthT = *(inbuffer + offset++);
+      if(cells_lengthT > cells_length)
+        this->cells = (geometry_msgs::Point*)realloc(this->cells, cells_lengthT * sizeof(geometry_msgs::Point));
+      offset += 3;
+      cells_length = cells_lengthT;
+      for( unsigned char i = 0; i < cells_length; i++){
+      offset += this->st_cells.deserialize(inbuffer + offset);
+        memcpy( &(this->cells[i]), &(this->st_cells), sizeof(geometry_msgs::Point));
+      }
+     return offset;
+    }
+
+   virtual const char * getType(){ return "nav_msgs/GridCells"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/MapMetaData.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,147 @@
+#ifndef ros_MapMetaData_h
+#define ros_MapMetaData_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "ros/time.h"
+#include "geometry_msgs/Pose.h"
+
+namespace nav_msgs
+{
+
+  class MapMetaData : public ros::Msg
+  {
+    public:
+      ros::Time map_load_time;
+      float resolution;
+      unsigned long width;
+      unsigned long height;
+      geometry_msgs::Pose origin;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_sec;
+      u_sec.real = this->map_load_time.sec;
+      *(outbuffer + offset + 0) = (u_sec.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_sec.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_sec.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_sec.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->map_load_time.sec);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_nsec;
+      u_nsec.real = this->map_load_time.nsec;
+      *(outbuffer + offset + 0) = (u_nsec.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_nsec.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_nsec.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_nsec.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->map_load_time.nsec);
+      union {
+        float real;
+        unsigned long base;
+      } u_resolution;
+      u_resolution.real = this->resolution;
+      *(outbuffer + offset + 0) = (u_resolution.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_resolution.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_resolution.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_resolution.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->resolution);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_width;
+      u_width.real = this->width;
+      *(outbuffer + offset + 0) = (u_width.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_width.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_width.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_width.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->width);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_height;
+      u_height.real = this->height;
+      *(outbuffer + offset + 0) = (u_height.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_height.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_height.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_height.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->height);
+      offset += this->origin.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_sec;
+      u_sec.base = 0;
+      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->map_load_time.sec = u_sec.real;
+      offset += sizeof(this->map_load_time.sec);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_nsec;
+      u_nsec.base = 0;
+      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->map_load_time.nsec = u_nsec.real;
+      offset += sizeof(this->map_load_time.nsec);
+      union {
+        float real;
+        unsigned long base;
+      } u_resolution;
+      u_resolution.base = 0;
+      u_resolution.base |= ((typeof(u_resolution.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_resolution.base |= ((typeof(u_resolution.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_resolution.base |= ((typeof(u_resolution.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_resolution.base |= ((typeof(u_resolution.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->resolution = u_resolution.real;
+      offset += sizeof(this->resolution);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_width;
+      u_width.base = 0;
+      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->width = u_width.real;
+      offset += sizeof(this->width);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_height;
+      u_height.base = 0;
+      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->height = u_height.real;
+      offset += sizeof(this->height);
+      offset += this->origin.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "nav_msgs/MapMetaData"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/OccupancyGrid.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,73 @@
+#ifndef ros_OccupancyGrid_h
+#define ros_OccupancyGrid_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/Header.h"
+#include "nav_msgs/MapMetaData.h"
+
+namespace nav_msgs
+{
+
+  class OccupancyGrid : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      nav_msgs::MapMetaData info;
+      unsigned char data_length;
+      signed char st_data;
+      signed char * data;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->info.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 {
+        signed char real;
+        unsigned char base;
+      } u_datai;
+      u_datai.real = this->data[i];
+      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->info.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));
+      offset += 3;
+      data_length = data_lengthT;
+      for( unsigned char i = 0; i < data_length; i++){
+      union {
+        signed char real;
+        unsigned char base;
+      } u_st_data;
+      u_st_data.base = 0;
+      u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->st_data = u_st_data.real;
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(signed char));
+      }
+     return offset;
+    }
+
+   virtual const char * getType(){ return "nav_msgs/OccupancyGrid"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/Odometry.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,59 @@
+#ifndef ros_Odometry_h
+#define ros_Odometry_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/PoseWithCovariance.h"
+#include "geometry_msgs/TwistWithCovariance.h"
+
+namespace nav_msgs
+{
+
+  class Odometry : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      char * child_frame_id;
+      geometry_msgs::PoseWithCovariance pose;
+      geometry_msgs::TwistWithCovariance twist;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      long * length_child_frame_id = (long *)(outbuffer + offset);
+      *length_child_frame_id = strlen( (const char*) this->child_frame_id);
+      offset += 4;
+      memcpy(outbuffer + offset, this->child_frame_id, *length_child_frame_id);
+      offset += *length_child_frame_id;
+      offset += this->pose.serialize(outbuffer + offset);
+      offset += this->twist.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint32_t length_child_frame_id = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_child_frame_id; ++k){
+          inbuffer[k-1]=inbuffer[k];
+           }
+      inbuffer[offset+length_child_frame_id-1]=0;
+      this->child_frame_id = (char *)(inbuffer + offset-1);
+      offset += length_child_frame_id;
+      offset += this->pose.deserialize(inbuffer + offset);
+      offset += this->twist.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "nav_msgs/Odometry"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/nav_msgs/Path.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,57 @@
+#ifndef ros_Path_h
+#define ros_Path_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/PoseStamped.h"
+
+namespace nav_msgs
+{
+
+  class Path : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      unsigned char poses_length;
+      geometry_msgs::PoseStamped st_poses;
+      geometry_msgs::PoseStamped * poses;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = poses_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( unsigned char i = 0; i < poses_length; i++){
+      offset += this->poses[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      unsigned char poses_lengthT = *(inbuffer + offset++);
+      if(poses_lengthT > poses_length)
+        this->poses = (geometry_msgs::PoseStamped*)realloc(this->poses, poses_lengthT * sizeof(geometry_msgs::PoseStamped));
+      offset += 3;
+      poses_length = poses_lengthT;
+      for( unsigned char i = 0; i < poses_length; i++){
+      offset += this->st_poses.deserialize(inbuffer + offset);
+        memcpy( &(this->poses[i]), &(this->st_poses), sizeof(geometry_msgs::PoseStamped));
+      }
+     return offset;
+    }
+
+   virtual const char * getType(){ return "nav_msgs/Path"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,51 @@
+/* 
+ * 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.
+ */
+
+/* 
+ * ROS definitions for Arduino
+ * Author: Michael Ferguson
+ */
+
+#ifndef ros_h
+#define ros_h
+
+#include "ros/ros_impl.h"
+#include "MbedHardware.h"
+
+namespace ros
+{
+  typedef NodeHandle_<MbedHardware> NodeHandle;
+}
+
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/duration.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,67 @@
+/* 
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2011, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ *  * Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  * Redistributions in binary form must reproduce the above
+ *    copyright notice, this list of conditions and the following
+ *    disclaimer in the documentation and/or other materials provided
+ *    with the distribution.
+ *  * Neither the name of Willow Garage, Inc. nor the names of its
+ *    contributors may be used to endorse or promote prducts derived
+ *    from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+/* 
+ * Author: Michael Ferguson
+ */
+
+#ifndef ros_duration_h_included
+#define ros_duration_h_included
+
+
+namespace ros
+{
+  void normalizeSecNSecSigned(long& sec, long& nsec);
+
+  class Duration
+  {
+    public:
+      long sec, nsec; 
+      
+      Duration() : sec(0), nsec(0) {}
+      Duration(long _sec, long _nsec) : sec(_sec), nsec(_nsec)
+      {
+        normalizeSecNSecSigned(sec, nsec);
+      }
+
+      Duration& operator+=(const Duration &rhs);
+      Duration& operator-=(const Duration &rhs);
+      Duration& operator*=(double scale);
+      
+  };
+
+}
+
+#endif
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/msg.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,22 @@
+/*
+ * Msg.h
+ *
+ *  Created on: Aug 5, 2011
+ *      Author: astambler
+ */
+
+#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;
+
+};
+}
+
+#endif /* MSG_H_ */
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/msg_receiver.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,27 @@
+/*
+ * msg_receiver.h
+ *
+ *  Created on: Aug 5, 2011
+ *      Author: astambler
+ */
+
+#ifndef MSG_RECEIVER_H_
+#define MSG_RECEIVER_H_
+
+namespace ros{
+
+/* Base class for objects recieving messages (Services and Subscribers) */
+  class MsgReceiver
+  {
+    public:
+        virtual void receive(unsigned char *data)=0;
+
+        //Distinguishes between different receiver types
+        virtual int _getType()=0;
+        virtual const char * getMsgType()=0;
+        int id_;
+        const char * topic_;
+  };
+}
+
+#endif /* MSG_RECEIVER_H_ */
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/node_handle.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,415 @@
+/*
+ * NodeHandle.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:
+ *
+ *  * 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_NODE_HANDLE_H_
+#define ROS_NODE_HANDLE_H_
+
+#include "../std_msgs/Time.h"
+#include "../rosserial_msgs/TopicInfo.h"
+#include "../rosserial_msgs/Log.h"
+#include "../rosserial_msgs/RequestParam.h"
+
+#define SYNC_SECONDS        5
+
+#define MODE_FIRST_FF       0
+#define MODE_SECOND_FF      1
+#define MODE_TOPIC_L        2   // waiting for topic id
+#define MODE_TOPIC_H        3
+#define MODE_SIZE_L         4   // waiting for message size
+#define MODE_SIZE_H         5
+#define MODE_MESSAGE        6
+#define MODE_CHECKSUM       7
+
+
+#define MSG_TIMEOUT 20  //20 milliseconds to recieve all of message data
+
+#include "node_output.h"
+
+#include "publisher.h"
+#include "msg_receiver.h"
+#include "subscriber.h"
+#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>
+class NodeHandle_ {
+
+protected:
+    Hardware hardware_;
+    NodeOutput<Hardware, OUTPUT_SIZE> no_;
+
+    /* time used for syncing */
+    unsigned long rt_time;
+
+    /* used for computing current time */
+    unsigned long sec_offset, nsec_offset;
+
+    unsigned char message_in[INPUT_SIZE];
+
+    Publisher * publishers[MAX_PUBLISHERS];
+    MsgReceiver * receivers[MAX_SUBSCRIBERS];
+
+    /******************************
+     *  Setup Functions
+     */
+public:
+    NodeHandle_() : no_(&hardware_) {
+    }
+
+    Hardware* getHardware() {
+        return &hardware_;
+    }
+
+    /* Start serial, initialize buffers */
+    void initNode() {
+        hardware_.init();
+        mode_ = 0;
+        bytes_ = 0;
+        index_ = 0;
+        topic_ = 0;
+        total_receivers=0;
+    };
+
+
+protected:
+
+    //State machine variables for spinOnce
+    int mode_;
+    int bytes_;
+    int topic_;
+    int index_;
+    int checksum_;
+
+    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;
+        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 */
+
+        unsigned long c_time = hardware_.time();
+
+        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
+            if (c_time > last_msg_timeout_time) {
+                mode_ = MODE_FIRST_FF;
+            }
+        }
+
+        /* while available buffer, read data */
+        while ( true ) {
+            short data = hardware_.read();
+            if ( data < 0 )
+                break;
+            checksum_ += data;
+            if ( mode_ == MODE_MESSAGE ) {      /* message data being recieved */
+                message_in[index_++] = data;
+                bytes_--;
+                if (bytes_ == 0)                  /* is message complete? if so, checksum */
+                    mode_ = MODE_CHECKSUM;
+            } else if ( mode_ == MODE_FIRST_FF ) {
+                if (data == 0xff) {
+                    mode_++;
+                    last_msg_timeout_time = c_time + MSG_TIMEOUT;
+                }
+            } else if ( mode_ == MODE_SECOND_FF ) {
+                if (data == 0xff) {
+                    mode_++;
+                } else {
+                    mode_ = MODE_FIRST_FF;
+                }
+            } else if ( mode_ == MODE_TOPIC_L ) {  /* bottom half of topic id */
+                topic_ = data;
+                mode_++;
+                checksum_ = data;                 /* first byte included in checksum */
+            } else if ( mode_ == MODE_TOPIC_H ) {  /* top half of topic id */
+                topic_ += data<<8;
+                mode_++;
+            } else if ( mode_ == MODE_SIZE_L ) { /* bottom half of message size */
+                bytes_ = data;
+                index_ = 0;
+                mode_++;
+            } else if ( mode_ == MODE_SIZE_H ) { /* top half of message size */
+                bytes_ += data<<8;
+                mode_ = MODE_MESSAGE;
+                if (bytes_ == 0)
+                    mode_ = MODE_CHECKSUM;
+            } else if ( mode_ == MODE_CHECKSUM ) { /* do checksum */
+                if ( (checksum_%256) == 255) {
+                    if (topic_ == TOPIC_NEGOTIATION) {
+                        requestSyncTime();
+                        negotiateTopics();
+                        last_sync_time = c_time;
+                        last_sync_receive_time = c_time;
+                    } else if (topic_ == TopicInfo::ID_TIME) {
+                        syncTime(message_in);
+                    } else if (topic_ == TopicInfo::ID_PARAMETER_REQUEST) {
+                        req_param_resp.deserialize(message_in);
+                        param_recieved= true;
+                    } else {
+                        if (receivers[topic_-100])
+                            receivers[topic_-100]->receive( message_in );
+                    }
+                }
+                mode_ = MODE_FIRST_FF;
+            }
+        }
+
+        /* occasionally sync time */
+        if ( no_.configured() && ((c_time-last_sync_time) > (SYNC_SECONDS*500) )) {
+            requestSyncTime();
+            last_sync_time = c_time;
+        }
+    }
+
+
+    /* Are we connected to the PC? */
+    bool connected() {
+        return no_.configured();
+    };
+
+    /**************************************************************
+     * Time functions
+     **************************************************************/
+
+    void requestSyncTime() {
+        std_msgs::Time t;
+        no_.publish( rosserial_msgs::TopicInfo::ID_TIME, &t);
+        rt_time = hardware_.time();
+    }
+
+    void syncTime( unsigned char * data ) {
+        std_msgs::Time t;
+        unsigned long offset = hardware_.time() - rt_time;
+
+        t.deserialize(data);
+
+        t.data.sec += offset/1000;
+        t.data.nsec += (offset%1000)*1000000UL;
+
+        this->setNow(t.data);
+        last_sync_receive_time = hardware_.time();
+    }
+
+
+
+    Time now() {
+        unsigned long ms = hardware_.time();
+        Time current_time;
+        current_time.sec = ms/1000 + sec_offset;
+        current_time.nsec = (ms%1000)*1000000UL + nsec_offset;
+        normalizeSecNSec(current_time.sec, current_time.nsec);
+        return current_time;
+    }
+
+    void setNow( Time & new_now ) {
+        unsigned long ms = hardware_.time();
+        sec_offset = new_now.sec - ms/1000 - 1;
+        nsec_offset = new_now.nsec - (ms%1000)*1000000UL + 1000000000UL;
+        normalizeSecNSec(sec_offset, nsec_offset);
+    }
+
+
+    /***************   Registeration    *****************************/
+    bool advertise(Publisher & p) {
+        int i;
+        for (i = 0; i < MAX_PUBLISHERS; i++) {
+            if (publishers[i] == 0) { // empty slot
+                publishers[i] = &p;
+                p.id_ = i+100+MAX_SUBSCRIBERS;
+                p.no_ = &this->no_;
+                return true;
+            }
+        }
+        return false;
+    }
+
+    /* Register a subscriber with the node */
+    template<typename MsgT>
+    bool subscribe(Subscriber< MsgT> &s) {
+        return registerReceiver((MsgReceiver*) &s);
+    }
+
+    template<typename SrvReq, typename SrvResp>
+    bool advertiseService(ServiceServer<SrvReq,SrvResp>& srv) {
+        srv.no_ = &no_;
+        return registerReceiver((MsgReceiver*) &srv);
+    }
+
+    void negotiateTopics() {
+        no_.setConfigured(true);
+
+        rosserial_msgs::TopicInfo ti;
+        int i;
+        for (i = 0; i < MAX_PUBLISHERS; i++) {
+            if (publishers[i] != 0) { // non-empty slot
+                ti.topic_id = publishers[i]->id_;
+                ti.topic_name = (char *) publishers[i]->topic_;
+                ti.message_type = (char *) publishers[i]->msg_->getType();
+                no_.publish( TOPIC_PUBLISHERS, &ti );
+            }
+        }
+        for (i = 0; i < MAX_SUBSCRIBERS; i++) {
+            if (receivers[i] != 0) { // non-empty slot
+                ti.topic_id = receivers[i]->id_;
+                ti.topic_name = (char *) receivers[i]->topic_;
+                ti.message_type = (char *) receivers[i]->getMsgType();
+                no_.publish( TOPIC_SUBSCRIBERS, &ti );
+            }
+        }
+    }
+
+    /*
+     * Logging
+     */
+private:
+    void log(char byte, const char * msg) {
+        rosserial_msgs::Log l;
+        l.level= byte;
+        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);
+    }
+    void loginfo(const char * msg) {
+        log(rosserial_msgs::Log::INFO, msg);
+    }
+    void logwarn(const char *msg) {
+        log(rosserial_msgs::Log::WARN, msg);
+    }
+    void logerror(const char*msg) {
+        log(rosserial_msgs::Log::ERROR, msg);
+    }
+    void logfatal(const char*msg) {
+        log(rosserial_msgs::Log::FATAL, msg);
+    }
+
+
+    /****************************************
+     * 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;
+        req.name  = (char*)name;
+        no_.publish(TopicInfo::ID_PARAMETER_REQUEST, &req);
+        int end_time = hardware_.time();
+        while (!param_recieved ) {
+            spinOnce();
+            if (end_time > hardware_.time()) return false;
+        }
+        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];
+                return true;
+            }
+        }
+        return false;
+    }
+    bool getParam(const char* name, float* param, int length=1) {
+        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];
+                return true;
+            }
+        }
+        return false;
+    }
+    bool getParam(const char* name, char** param, int length=1) {
+        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]);
+                return true;
+            }
+        }
+        return false;
+
+    }
+
+};
+
+
+
+}
+
+#endif /* NODEHANDLE_H_ */
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/node_output.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,79 @@
+/*
+ * NodeOutput.h
+ *
+ *  Created on: Aug 5, 2011
+ *      Author: astambler
+ */
+
+#ifndef NODEOUTPUT_H_
+#define NODEOUTPUT_H_
+
+/*
+ * 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_ {
+
+private:
+    Hardware* hardware_;
+    bool configured_;
+    unsigned char message_out[OUTSIZE];
+
+public:
+    NodeOutput(Hardware* h) {
+        hardware_ = h;
+        configured_ = false;
+    }
+
+    NodeOutput() {};
+    void setHardware(Hardware* h) {
+        hardware_  = h;
+        configured_=false;
+    }
+
+    void setConfigured(bool b) {
+        configured_ =b;
+    }
+    bool configured() {
+        return configured_;
+    };
+
+    virtual int  publish(short id, Msg * msg) {
+        if (!configured_) return 0;
+
+        //short test_id,test_off;
+        /* serialize message */
+        short l = msg->serialize(message_out+6);
+
+        /* setup the header */
+        message_out[0] = 0xff;
+        message_out[1] = 0xff;
+        message_out[2] = (unsigned char) id&255;
+        message_out[3] = (unsigned char) id>>8;
+        message_out[4] = (unsigned char) l&255;
+        message_out[5] = ((unsigned char) l>>8);
+
+        /* calculate checksum */
+        short chk = 0;
+        for (int i =2; i<l+6; i++)
+            chk += message_out[i];
+        message_out[6+l] = 255 - (chk%256);
+
+        hardware_->write(message_out, 6+l+1);
+        return 1;
+    }
+};
+}
+#endif /* NODEOUTPUT_H_ */
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/publisher.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,34 @@
+/*
+ * publisher.h
+ *
+ *  Created on: Aug 5, 2011
+ *      Author: astambler
+ */
+
+#ifndef PUBLISHER_H_
+#define PUBLISHER_H_
+
+#include "node_output.h"
+
+namespace ros{
+  /* Generic Publisher */
+
+  class Publisher
+  {
+    public:
+      Publisher( const char * topic_name, Msg * msg ): topic_(topic_name), msg_(msg){};
+      int publish( Msg * msg ){
+          return no_->publish(id_, msg_);
+      };
+
+      const char * topic_;
+
+      Msg *msg_;
+      int id_;
+      NodeOutput_* no_;
+  };
+
+}
+
+
+#endif /* PUBLISHER_H_ */
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/ros_impl.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,44 @@
+/* 
+ * 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/rosserial_ids.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,16 @@
+/*
+ * rosserial_ids.h
+ *
+ *  Created on: Aug 5, 2011
+ *      Author: astambler
+ */
+
+#ifndef ROSSERIAL_IDS_H_
+#define ROSSERIAL_IDS_H_
+
+#define TOPIC_NEGOTIATION   0
+#define TOPIC_PUBLISHERS    0
+#define TOPIC_SUBSCRIBERS   1
+#define TOPIC_SERVICES      2
+
+#endif /* ROSSERIAL_IDS_H_ */
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/service_server.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,54 @@
+/*
+ * service_server.h
+ *
+ *  Created on: Aug 5, 2011
+ *      Author: astambler
+ */
+
+
+#ifndef SERVICE_SERVER_H_
+#define SERVICE_SERVER_H_
+
+
+#include "node_output.h"
+
+namespace ros{
+template<typename SrvRequest , typename SrvResponse>
+  class ServiceServer : MsgReceiver{
+  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;
+      }
+
+      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);
+      }
+
+    virtual int _getType(){
+        return 3;
+    }
+    virtual const char * getMsgType(){
+        return req.getType();
+    }
+
+      SrvRequest req;
+      SrvResponse resp;
+      NodeOutput_ * no_;
+
+  };
+}
+
+#endif /* SERVICE_SERVER_H_ */
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/subscriber.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,42 @@
+/*
+ * subscriber.h
+ *
+ *  Created on: Aug 5, 2011
+ *      Author: astambler
+ */
+
+#ifndef SUBSCRIBER_H_
+#define SUBSCRIBER_H_
+
+#include "rosserial_ids.h"
+#include "msg_receiver.h"
+namespace ros{
+
+/* ROS Subscriber
+ * This class handles holding the msg so that
+ * it is not continously reallocated.  It is also used by the
+ * node handle to keep track of callback functions and IDs.
+ */
+template<typename MsgT>
+class Subscriber: public MsgReceiver{
+  public:
+
+      typedef void(*CallbackT)(const MsgT&);
+
+      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);
+      }
+    virtual const char * getMsgType(){return this->msg.getType();}
+    virtual int _getType(){return TOPIC_SUBSCRIBERS;}
+  private:
+    CallbackT cb_;
+};
+
+}
+#endif /* SUBSCRIBER_H_ */
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros/time.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,88 @@
+/*
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2011, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ *  * Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  * Redistributions in binary form must reproduce the above
+ *    copyright notice, this list of conditions and the following
+ *    disclaimer in the documentation and/or other materials provided
+ *    with the distribution.
+ *  * Neither the name of Willow Garage, Inc. nor the names of its
+ *    contributors may be used to endorse or promote prducts derived
+ *    from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+/*
+ * Author: Michael Ferguson
+ */
+
+#ifndef ros_time_h_included
+#define ros_time_h_included
+
+#include <ros/duration.h>
+#include <math.h>
+
+
+namespace ros {
+void normalizeSecNSec(unsigned long &sec, unsigned long &nsec);
+
+
+class Time {
+public:
+    unsigned long sec, nsec;
+
+    Time() : sec(0), nsec(0) {}
+    Time(unsigned long _sec, unsigned long _nsec) : sec(_sec), nsec(_nsec) {
+        normalizeSecNSec(sec, nsec);
+    }
+
+    double toSec() const {
+        return (double)sec + 1e-9*(double)nsec;
+    };
+    void fromSec(double t) {
+        sec = (unsigned long) floor(t);
+        nsec = (unsigned long) round((t-sec) * 1e9);
+    };
+
+    unsigned long toNsec() {
+        return (unsigned long)sec*1000000000ull + (unsigned long)nsec;
+    };
+    Time& fromNSec(long t);
+
+    Time& operator +=(const Duration &rhs);
+    Time& operator -=(const Duration &rhs);
+
+    static Time now();
+    static void setNow( Time & new_now);
+
+    int round(double x) {
+        int a;
+        a = floor(x + 0.5);
+        return a;
+    }
+
+
+};
+}
+
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosserial_mbed/Adc.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,141 @@
+#ifndef ros_Adc_h
+#define ros_Adc_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace rosserial_mbed
+{
+
+  class Adc : public ros::Msg
+  {
+    public:
+      unsigned short adc0;
+      unsigned short adc1;
+      unsigned short adc2;
+      unsigned short adc3;
+      unsigned short adc4;
+      unsigned short adc5;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      union {
+        unsigned short real;
+        unsigned short base;
+      } u_adc0;
+      u_adc0.real = this->adc0;
+      *(outbuffer + offset + 0) = (u_adc0.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_adc0.base >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->adc0);
+      union {
+        unsigned short real;
+        unsigned short base;
+      } u_adc1;
+      u_adc1.real = this->adc1;
+      *(outbuffer + offset + 0) = (u_adc1.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_adc1.base >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->adc1);
+      union {
+        unsigned short real;
+        unsigned short base;
+      } u_adc2;
+      u_adc2.real = this->adc2;
+      *(outbuffer + offset + 0) = (u_adc2.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_adc2.base >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->adc2);
+      union {
+        unsigned short real;
+        unsigned short base;
+      } u_adc3;
+      u_adc3.real = this->adc3;
+      *(outbuffer + offset + 0) = (u_adc3.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_adc3.base >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->adc3);
+      union {
+        unsigned short real;
+        unsigned short base;
+      } u_adc4;
+      u_adc4.real = this->adc4;
+      *(outbuffer + offset + 0) = (u_adc4.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_adc4.base >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->adc4);
+      union {
+        unsigned short real;
+        unsigned short base;
+      } u_adc5;
+      u_adc5.real = this->adc5;
+      *(outbuffer + offset + 0) = (u_adc5.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_adc5.base >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->adc5);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        unsigned short real;
+        unsigned short base;
+      } u_adc0;
+      u_adc0.base = 0;
+      u_adc0.base |= ((typeof(u_adc0.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_adc0.base |= ((typeof(u_adc0.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->adc0 = u_adc0.real;
+      offset += sizeof(this->adc0);
+      union {
+        unsigned short real;
+        unsigned short base;
+      } u_adc1;
+      u_adc1.base = 0;
+      u_adc1.base |= ((typeof(u_adc1.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_adc1.base |= ((typeof(u_adc1.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->adc1 = u_adc1.real;
+      offset += sizeof(this->adc1);
+      union {
+        unsigned short real;
+        unsigned short base;
+      } u_adc2;
+      u_adc2.base = 0;
+      u_adc2.base |= ((typeof(u_adc2.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_adc2.base |= ((typeof(u_adc2.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->adc2 = u_adc2.real;
+      offset += sizeof(this->adc2);
+      union {
+        unsigned short real;
+        unsigned short base;
+      } u_adc3;
+      u_adc3.base = 0;
+      u_adc3.base |= ((typeof(u_adc3.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_adc3.base |= ((typeof(u_adc3.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->adc3 = u_adc3.real;
+      offset += sizeof(this->adc3);
+      union {
+        unsigned short real;
+        unsigned short base;
+      } u_adc4;
+      u_adc4.base = 0;
+      u_adc4.base |= ((typeof(u_adc4.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_adc4.base |= ((typeof(u_adc4.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->adc4 = u_adc4.real;
+      offset += sizeof(this->adc4);
+      union {
+        unsigned short real;
+        unsigned short base;
+      } u_adc5;
+      u_adc5.base = 0;
+      u_adc5.base |= ((typeof(u_adc5.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_adc5.base |= ((typeof(u_adc5.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->adc5 = u_adc5.real;
+      offset += sizeof(this->adc5);
+     return offset;
+    }
+
+    virtual const char * getType(){ return "rosserial_mbed/Adc"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosserial_msgs/Log.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,68 @@
+#ifndef ros_Log_h
+#define ros_Log_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace rosserial_msgs
+{
+
+  class Log : public ros::Msg
+  {
+    public:
+      unsigned char level;
+      char * msg;
+      enum { DEBUG = 0 };
+      enum { INFO = 1 };
+      enum { WARN = 2 };
+      enum { ERROR = 3 };
+      enum { FATAL = 4 };
+
+    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_msg = (long *)(outbuffer + offset);
+      *length_msg = strlen( (const char*) this->msg);
+      offset += 4;
+      memcpy(outbuffer + offset, this->msg, *length_msg);
+      offset += *length_msg;
+      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_msg = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_msg; ++k){
+          inbuffer[k-1]=inbuffer[k];
+           }
+      inbuffer[offset+length_msg-1]=0;
+      this->msg = (char *)(inbuffer + offset-1);
+      offset += length_msg;
+     return offset;
+    }
+
+    virtual const char * getType(){ return "rosserial_msgs/Log"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosserial_msgs/RequestParam.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,174 @@
+#ifndef ros_SERVICE_RequestParam_h
+#define ros_SERVICE_RequestParam_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace rosserial_msgs
+{
+
+static const char REQUESTPARAM[] = "rosserial_msgs/RequestParam";
+
+  class RequestParamRequest : public ros::Msg
+  {
+    public:
+      char * name;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      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;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_name = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+           }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+     return offset;
+    }
+
+    virtual const char * getType(){ return REQUESTPARAM; };
+
+  };
+
+  class RequestParamResponse : public ros::Msg
+  {
+    public:
+      unsigned char ints_length;
+      long st_ints;
+      long * ints;
+      unsigned char floats_length;
+      float st_floats;
+      float * floats;
+      unsigned char strings_length;
+      char* st_strings;
+      char* * strings;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = ints_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( unsigned char i = 0; i < ints_length; i++){
+      union {
+        long real;
+        unsigned long base;
+      } u_intsi;
+      u_intsi.real = this->ints[i];
+      *(outbuffer + offset + 0) = (u_intsi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_intsi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_intsi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_intsi.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->ints[i]);
+      }
+      *(outbuffer + offset++) = floats_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( unsigned char i = 0; i < floats_length; i++){
+      union {
+        float real;
+        unsigned long base;
+      } u_floatsi;
+      u_floatsi.real = this->floats[i];
+      *(outbuffer + offset + 0) = (u_floatsi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_floatsi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_floatsi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_floatsi.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->floats[i]);
+      }
+      *(outbuffer + offset++) = strings_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( unsigned char i = 0; i < strings_length; i++){
+      long * length_stringsi = (long *)(outbuffer + offset);
+      *length_stringsi = strlen( (const char*) this->strings[i]);
+      offset += 4;
+      memcpy(outbuffer + offset, this->strings[i], *length_stringsi);
+      offset += *length_stringsi;
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      unsigned char ints_lengthT = *(inbuffer + offset++);
+      if(ints_lengthT > ints_length)
+        this->ints = (long*)realloc(this->ints, ints_lengthT * sizeof(long));
+      offset += 3;
+      ints_length = ints_lengthT;
+      for( unsigned char i = 0; i < ints_length; i++){
+      union {
+        long real;
+        unsigned long base;
+      } u_st_ints;
+      u_st_ints.base = 0;
+      u_st_ints.base |= ((typeof(u_st_ints.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_ints.base |= ((typeof(u_st_ints.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_ints.base |= ((typeof(u_st_ints.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_ints.base |= ((typeof(u_st_ints.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->st_ints = u_st_ints.real;
+      offset += sizeof(this->st_ints);
+        memcpy( &(this->ints[i]), &(this->st_ints), sizeof(long));
+      }
+      unsigned char floats_lengthT = *(inbuffer + offset++);
+      if(floats_lengthT > floats_length)
+        this->floats = (float*)realloc(this->floats, floats_lengthT * sizeof(float));
+      offset += 3;
+      floats_length = floats_lengthT;
+      for( unsigned char i = 0; i < floats_length; i++){
+      union {
+        float real;
+        unsigned long base;
+      } u_st_floats;
+      u_st_floats.base = 0;
+      u_st_floats.base |= ((typeof(u_st_floats.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_floats.base |= ((typeof(u_st_floats.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_floats.base |= ((typeof(u_st_floats.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_floats.base |= ((typeof(u_st_floats.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->st_floats = u_st_floats.real;
+      offset += sizeof(this->st_floats);
+        memcpy( &(this->floats[i]), &(this->st_floats), sizeof(float));
+      }
+      unsigned char strings_lengthT = *(inbuffer + offset++);
+      if(strings_lengthT > strings_length)
+        this->strings = (char**)realloc(this->strings, strings_lengthT * sizeof(char*));
+      offset += 3;
+      strings_length = strings_lengthT;
+      for( unsigned char i = 0; i < strings_length; i++){
+      uint32_t length_st_strings = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_strings; ++k){
+          inbuffer[k-1]=inbuffer[k];
+           }
+      inbuffer[offset+length_st_strings-1]=0;
+      this->st_strings = (char *)(inbuffer + offset-1);
+      offset += length_st_strings;
+        memcpy( &(this->strings[i]), &(this->st_strings), sizeof(char*));
+      }
+     return offset;
+    }
+
+   virtual const char * getType(){ return REQUESTPARAM; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosserial_msgs/TopicInfo.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,86 @@
+#ifndef ros_TopicInfo_h
+#define ros_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;
+      enum { ID_PUBLISHER = 0 };
+      enum { ID_SUBSCRIBER = 1 };
+      enum { ID_SERVICE_SERVER = 2 };
+      enum { ID_SERVICE_CLIENT = 3 };
+      enum { ID_PARAMETER_REQUEST = 4 };
+      enum { ID_LOG = 5 };
+      enum { ID_TIME = 10 };
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      union {
+        unsigned short real;
+        unsigned short 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;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        unsigned short real;
+        unsigned short base;
+      } u_topic_id;
+      u_topic_id.base = 0;
+      u_topic_id.base |= ((typeof(u_topic_id.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_topic_id.base |= ((typeof(u_topic_id.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->topic_id = u_topic_id.real;
+      offset += sizeof(this->topic_id);
+      uint32_t length_topic_name = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_topic_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+           }
+      inbuffer[offset+length_topic_name-1]=0;
+      this->topic_name = (char *)(inbuffer + offset-1);
+      offset += length_topic_name;
+      uint32_t length_message_type = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_message_type; ++k){
+          inbuffer[k-1]=inbuffer[k];
+           }
+      inbuffer[offset+length_message_type-1]=0;
+      this->message_type = (char *)(inbuffer + offset-1);
+      offset += length_message_type;
+     return offset;
+    }
+
+    virtual const char * getType(){ return "rosserial_msgs/TopicInfo"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/CameraInfo.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,281 @@
+#ifndef ros_CameraInfo_h
+#define ros_CameraInfo_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/Header.h"
+#include "sensor_msgs/RegionOfInterest.h"
+
+namespace sensor_msgs
+{
+
+  class CameraInfo : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      unsigned long height;
+      unsigned long width;
+      char * distortion_model;
+      unsigned char D_length;
+      float st_D;
+      float * D;
+      float K[9];
+      float R[9];
+      float P[12];
+      unsigned long binning_x;
+      unsigned long binning_y;
+      sensor_msgs::RegionOfInterest roi;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_height;
+      u_height.real = this->height;
+      *(outbuffer + offset + 0) = (u_height.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_height.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_height.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_height.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->height);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_width;
+      u_width.real = this->width;
+      *(outbuffer + offset + 0) = (u_width.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_width.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_width.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_width.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->width);
+      long * length_distortion_model = (long *)(outbuffer + offset);
+      *length_distortion_model = strlen( (const char*) this->distortion_model);
+      offset += 4;
+      memcpy(outbuffer + offset, this->distortion_model, *length_distortion_model);
+      offset += *length_distortion_model;
+      *(outbuffer + offset++) = D_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( unsigned char i = 0; i < D_length; i++){
+      long * val_Di = (long *) &(this->D[i]);
+      long exp_Di = (((*val_Di)>>23)&255);
+      if(exp_Di != 0)
+        exp_Di += 1023-127;
+      long sig_Di = *val_Di;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = (sig_Di<<5) & 0xff;
+      *(outbuffer + offset++) = (sig_Di>>3) & 0xff;
+      *(outbuffer + offset++) = (sig_Di>>11) & 0xff;
+      *(outbuffer + offset++) = ((exp_Di<<4) & 0xF0) | ((sig_Di>>19)&0x0F);
+      *(outbuffer + offset++) = (exp_Di>>4) & 0x7F;
+      if(this->D[i] < 0) *(outbuffer + offset -1) |= 0x80;
+      }
+      unsigned char * K_val = (unsigned char *) this->K;
+      for( unsigned char i = 0; i < 9; i++){
+      long * val_Ki = (long *) &(this->K[i]);
+      long exp_Ki = (((*val_Ki)>>23)&255);
+      if(exp_Ki != 0)
+        exp_Ki += 1023-127;
+      long sig_Ki = *val_Ki;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = (sig_Ki<<5) & 0xff;
+      *(outbuffer + offset++) = (sig_Ki>>3) & 0xff;
+      *(outbuffer + offset++) = (sig_Ki>>11) & 0xff;
+      *(outbuffer + offset++) = ((exp_Ki<<4) & 0xF0) | ((sig_Ki>>19)&0x0F);
+      *(outbuffer + offset++) = (exp_Ki>>4) & 0x7F;
+      if(this->K[i] < 0) *(outbuffer + offset -1) |= 0x80;
+      }
+      unsigned char * R_val = (unsigned char *) this->R;
+      for( unsigned char i = 0; i < 9; i++){
+      long * val_Ri = (long *) &(this->R[i]);
+      long exp_Ri = (((*val_Ri)>>23)&255);
+      if(exp_Ri != 0)
+        exp_Ri += 1023-127;
+      long sig_Ri = *val_Ri;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = (sig_Ri<<5) & 0xff;
+      *(outbuffer + offset++) = (sig_Ri>>3) & 0xff;
+      *(outbuffer + offset++) = (sig_Ri>>11) & 0xff;
+      *(outbuffer + offset++) = ((exp_Ri<<4) & 0xF0) | ((sig_Ri>>19)&0x0F);
+      *(outbuffer + offset++) = (exp_Ri>>4) & 0x7F;
+      if(this->R[i] < 0) *(outbuffer + offset -1) |= 0x80;
+      }
+      unsigned char * P_val = (unsigned char *) this->P;
+      for( unsigned char i = 0; i < 12; i++){
+      long * val_Pi = (long *) &(this->P[i]);
+      long exp_Pi = (((*val_Pi)>>23)&255);
+      if(exp_Pi != 0)
+        exp_Pi += 1023-127;
+      long sig_Pi = *val_Pi;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = (sig_Pi<<5) & 0xff;
+      *(outbuffer + offset++) = (sig_Pi>>3) & 0xff;
+      *(outbuffer + offset++) = (sig_Pi>>11) & 0xff;
+      *(outbuffer + offset++) = ((exp_Pi<<4) & 0xF0) | ((sig_Pi>>19)&0x0F);
+      *(outbuffer + offset++) = (exp_Pi>>4) & 0x7F;
+      if(this->P[i] < 0) *(outbuffer + offset -1) |= 0x80;
+      }
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_binning_x;
+      u_binning_x.real = this->binning_x;
+      *(outbuffer + offset + 0) = (u_binning_x.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_binning_x.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_binning_x.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_binning_x.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->binning_x);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_binning_y;
+      u_binning_y.real = this->binning_y;
+      *(outbuffer + offset + 0) = (u_binning_y.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_binning_y.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_binning_y.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_binning_y.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->binning_y);
+      offset += this->roi.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_height;
+      u_height.base = 0;
+      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->height = u_height.real;
+      offset += sizeof(this->height);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_width;
+      u_width.base = 0;
+      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->width = u_width.real;
+      offset += sizeof(this->width);
+      uint32_t length_distortion_model = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_distortion_model; ++k){
+          inbuffer[k-1]=inbuffer[k];
+           }
+      inbuffer[offset+length_distortion_model-1]=0;
+      this->distortion_model = (char *)(inbuffer + offset-1);
+      offset += length_distortion_model;
+      unsigned char D_lengthT = *(inbuffer + offset++);
+      if(D_lengthT > D_length)
+        this->D = (float*)realloc(this->D, D_lengthT * sizeof(float));
+      offset += 3;
+      D_length = D_lengthT;
+      for( unsigned char i = 0; i < D_length; i++){
+      unsigned long * val_st_D = (unsigned long*) &(this->st_D);
+      offset += 3;
+      *val_st_D = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_st_D |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_st_D |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_st_D |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
+      unsigned long exp_st_D = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_st_D |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      if(exp_st_D !=0)
+        *val_st_D |= ((exp_st_D)-1023+127)<<23;
+      if( ((*(inbuffer+offset++)) & 0x80) > 0) this->st_D = -this->st_D;
+        memcpy( &(this->D[i]), &(this->st_D), sizeof(float));
+      }
+      unsigned char * K_val = (unsigned char *) this->K;
+      for( unsigned char i = 0; i < 9; i++){
+      unsigned long * val_Ki = (unsigned long*) &(this->K[i]);
+      offset += 3;
+      *val_Ki = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_Ki |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_Ki |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_Ki |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
+      unsigned long exp_Ki = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_Ki |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      if(exp_Ki !=0)
+        *val_Ki |= ((exp_Ki)-1023+127)<<23;
+      if( ((*(inbuffer+offset++)) & 0x80) > 0) this->K[i] = -this->K[i];
+      }
+      unsigned char * R_val = (unsigned char *) this->R;
+      for( unsigned char i = 0; i < 9; i++){
+      unsigned long * val_Ri = (unsigned long*) &(this->R[i]);
+      offset += 3;
+      *val_Ri = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_Ri |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_Ri |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_Ri |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
+      unsigned long exp_Ri = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_Ri |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      if(exp_Ri !=0)
+        *val_Ri |= ((exp_Ri)-1023+127)<<23;
+      if( ((*(inbuffer+offset++)) & 0x80) > 0) this->R[i] = -this->R[i];
+      }
+      unsigned char * P_val = (unsigned char *) this->P;
+      for( unsigned char i = 0; i < 12; i++){
+      unsigned long * val_Pi = (unsigned long*) &(this->P[i]);
+      offset += 3;
+      *val_Pi = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_Pi |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_Pi |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_Pi |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
+      unsigned long exp_Pi = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_Pi |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      if(exp_Pi !=0)
+        *val_Pi |= ((exp_Pi)-1023+127)<<23;
+      if( ((*(inbuffer+offset++)) & 0x80) > 0) this->P[i] = -this->P[i];
+      }
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_binning_x;
+      u_binning_x.base = 0;
+      u_binning_x.base |= ((typeof(u_binning_x.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_binning_x.base |= ((typeof(u_binning_x.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_binning_x.base |= ((typeof(u_binning_x.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_binning_x.base |= ((typeof(u_binning_x.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->binning_x = u_binning_x.real;
+      offset += sizeof(this->binning_x);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_binning_y;
+      u_binning_y.base = 0;
+      u_binning_y.base |= ((typeof(u_binning_y.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_binning_y.base |= ((typeof(u_binning_y.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_binning_y.base |= ((typeof(u_binning_y.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_binning_y.base |= ((typeof(u_binning_y.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->binning_y = u_binning_y.real;
+      offset += sizeof(this->binning_y);
+      offset += this->roi.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "sensor_msgs/CameraInfo"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/ChannelFloat32.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,85 @@
+#ifndef ros_ChannelFloat32_h
+#define ros_ChannelFloat32_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace sensor_msgs
+{
+
+  class ChannelFloat32 : public ros::Msg
+  {
+    public:
+      char * name;
+      unsigned char values_length;
+      float st_values;
+      float * values;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      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;
+      *(outbuffer + offset++) = values_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( unsigned char i = 0; i < values_length; i++){
+      union {
+        float real;
+        unsigned long base;
+      } u_valuesi;
+      u_valuesi.real = this->values[i];
+      *(outbuffer + offset + 0) = (u_valuesi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_valuesi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_valuesi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_valuesi.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->values[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_name = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+           }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+      unsigned char values_lengthT = *(inbuffer + offset++);
+      if(values_lengthT > values_length)
+        this->values = (float*)realloc(this->values, values_lengthT * sizeof(float));
+      offset += 3;
+      values_length = values_lengthT;
+      for( unsigned char i = 0; i < values_length; i++){
+      union {
+        float real;
+        unsigned long base;
+      } u_st_values;
+      u_st_values.base = 0;
+      u_st_values.base |= ((typeof(u_st_values.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_values.base |= ((typeof(u_st_values.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_values.base |= ((typeof(u_st_values.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_values.base |= ((typeof(u_st_values.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->st_values = u_st_values.real;
+      offset += sizeof(this->st_values);
+        memcpy( &(this->values[i]), &(this->st_values), sizeof(float));
+      }
+     return offset;
+    }
+
+   virtual const char * getType(){ return "sensor_msgs/ChannelFloat32"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/CompressedImage.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,83 @@
+#ifndef ros_CompressedImage_h
+#define ros_CompressedImage_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/Header.h"
+
+namespace sensor_msgs
+{
+
+  class CompressedImage : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      char * format;
+      unsigned char data_length;
+      unsigned char st_data;
+      unsigned char * data;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      long * length_format = (long *)(outbuffer + offset);
+      *length_format = strlen( (const char*) this->format);
+      offset += 4;
+      memcpy(outbuffer + offset, this->format, *length_format);
+      offset += *length_format;
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( unsigned char i = 0; i < data_length; i++){
+      union {
+        unsigned char real;
+        unsigned char base;
+      } u_datai;
+      u_datai.real = this->data[i];
+      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      uint32_t length_format = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_format; ++k){
+          inbuffer[k-1]=inbuffer[k];
+           }
+      inbuffer[offset+length_format-1]=0;
+      this->format = (char *)(inbuffer + offset-1);
+      offset += length_format;
+      unsigned char data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (unsigned char*)realloc(this->data, data_lengthT * sizeof(unsigned char));
+      offset += 3;
+      data_length = data_lengthT;
+      for( unsigned char i = 0; i < data_length; i++){
+      union {
+        unsigned char real;
+        unsigned char base;
+      } u_st_data;
+      u_st_data.base = 0;
+      u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->st_data = u_st_data.real;
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(unsigned char));
+      }
+     return offset;
+    }
+
+   virtual const char * getType(){ return "sensor_msgs/CompressedImage"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/Image.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,165 @@
+#ifndef ros_Image_h
+#define ros_Image_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/Header.h"
+
+namespace sensor_msgs
+{
+
+  class Image : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      unsigned long height;
+      unsigned long width;
+      char * encoding;
+      unsigned char is_bigendian;
+      unsigned long step;
+      unsigned char data_length;
+      unsigned char st_data;
+      unsigned char * data;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_height;
+      u_height.real = this->height;
+      *(outbuffer + offset + 0) = (u_height.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_height.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_height.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_height.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->height);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_width;
+      u_width.real = this->width;
+      *(outbuffer + offset + 0) = (u_width.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_width.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_width.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_width.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->width);
+      long * length_encoding = (long *)(outbuffer + offset);
+      *length_encoding = strlen( (const char*) this->encoding);
+      offset += 4;
+      memcpy(outbuffer + offset, this->encoding, *length_encoding);
+      offset += *length_encoding;
+      union {
+        unsigned char real;
+        unsigned char base;
+      } u_is_bigendian;
+      u_is_bigendian.real = this->is_bigendian;
+      *(outbuffer + offset + 0) = (u_is_bigendian.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->is_bigendian);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_step;
+      u_step.real = this->step;
+      *(outbuffer + offset + 0) = (u_step.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_step.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_step.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_step.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->step);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( unsigned char i = 0; i < data_length; i++){
+      union {
+        unsigned char real;
+        unsigned char base;
+      } u_datai;
+      u_datai.real = this->data[i];
+      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_height;
+      u_height.base = 0;
+      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->height = u_height.real;
+      offset += sizeof(this->height);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_width;
+      u_width.base = 0;
+      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->width = u_width.real;
+      offset += sizeof(this->width);
+      uint32_t length_encoding = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_encoding; ++k){
+          inbuffer[k-1]=inbuffer[k];
+           }
+      inbuffer[offset+length_encoding-1]=0;
+      this->encoding = (char *)(inbuffer + offset-1);
+      offset += length_encoding;
+      union {
+        unsigned char real;
+        unsigned char base;
+      } u_is_bigendian;
+      u_is_bigendian.base = 0;
+      u_is_bigendian.base |= ((typeof(u_is_bigendian.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->is_bigendian = u_is_bigendian.real;
+      offset += sizeof(this->is_bigendian);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_step;
+      u_step.base = 0;
+      u_step.base |= ((typeof(u_step.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_step.base |= ((typeof(u_step.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_step.base |= ((typeof(u_step.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_step.base |= ((typeof(u_step.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->step = u_step.real;
+      offset += sizeof(this->step);
+      unsigned char data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (unsigned char*)realloc(this->data, data_lengthT * sizeof(unsigned char));
+      offset += 3;
+      data_length = data_lengthT;
+      for( unsigned char i = 0; i < data_length; i++){
+      union {
+        unsigned char real;
+        unsigned char base;
+      } u_st_data;
+      u_st_data.base = 0;
+      u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->st_data = u_st_data.real;
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(unsigned char));
+      }
+     return offset;
+    }
+
+   virtual const char * getType(){ return "sensor_msgs/Image"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/Imu.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,144 @@
+#ifndef ros_Imu_h
+#define ros_Imu_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Quaternion.h"
+#include "geometry_msgs/Vector3.h"
+
+namespace sensor_msgs
+{
+
+  class Imu : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      geometry_msgs::Quaternion orientation;
+      float orientation_covariance[9];
+      geometry_msgs::Vector3 angular_velocity;
+      float angular_velocity_covariance[9];
+      geometry_msgs::Vector3 linear_acceleration;
+      float linear_acceleration_covariance[9];
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->orientation.serialize(outbuffer + offset);
+      unsigned char * orientation_covariance_val = (unsigned char *) this->orientation_covariance;
+      for( unsigned char i = 0; i < 9; i++){
+      long * val_orientation_covariancei = (long *) &(this->orientation_covariance[i]);
+      long exp_orientation_covariancei = (((*val_orientation_covariancei)>>23)&255);
+      if(exp_orientation_covariancei != 0)
+        exp_orientation_covariancei += 1023-127;
+      long sig_orientation_covariancei = *val_orientation_covariancei;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = (sig_orientation_covariancei<<5) & 0xff;
+      *(outbuffer + offset++) = (sig_orientation_covariancei>>3) & 0xff;
+      *(outbuffer + offset++) = (sig_orientation_covariancei>>11) & 0xff;
+      *(outbuffer + offset++) = ((exp_orientation_covariancei<<4) & 0xF0) | ((sig_orientation_covariancei>>19)&0x0F);
+      *(outbuffer + offset++) = (exp_orientation_covariancei>>4) & 0x7F;
+      if(this->orientation_covariance[i] < 0) *(outbuffer + offset -1) |= 0x80;
+      }
+      offset += this->angular_velocity.serialize(outbuffer + offset);
+      unsigned char * angular_velocity_covariance_val = (unsigned char *) this->angular_velocity_covariance;
+      for( unsigned char i = 0; i < 9; i++){
+      long * val_angular_velocity_covariancei = (long *) &(this->angular_velocity_covariance[i]);
+      long exp_angular_velocity_covariancei = (((*val_angular_velocity_covariancei)>>23)&255);
+      if(exp_angular_velocity_covariancei != 0)
+        exp_angular_velocity_covariancei += 1023-127;
+      long sig_angular_velocity_covariancei = *val_angular_velocity_covariancei;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = (sig_angular_velocity_covariancei<<5) & 0xff;
+      *(outbuffer + offset++) = (sig_angular_velocity_covariancei>>3) & 0xff;
+      *(outbuffer + offset++) = (sig_angular_velocity_covariancei>>11) & 0xff;
+      *(outbuffer + offset++) = ((exp_angular_velocity_covariancei<<4) & 0xF0) | ((sig_angular_velocity_covariancei>>19)&0x0F);
+      *(outbuffer + offset++) = (exp_angular_velocity_covariancei>>4) & 0x7F;
+      if(this->angular_velocity_covariance[i] < 0) *(outbuffer + offset -1) |= 0x80;
+      }
+      offset += this->linear_acceleration.serialize(outbuffer + offset);
+      unsigned char * linear_acceleration_covariance_val = (unsigned char *) this->linear_acceleration_covariance;
+      for( unsigned char i = 0; i < 9; i++){
+      long * val_linear_acceleration_covariancei = (long *) &(this->linear_acceleration_covariance[i]);
+      long exp_linear_acceleration_covariancei = (((*val_linear_acceleration_covariancei)>>23)&255);
+      if(exp_linear_acceleration_covariancei != 0)
+        exp_linear_acceleration_covariancei += 1023-127;
+      long sig_linear_acceleration_covariancei = *val_linear_acceleration_covariancei;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = (sig_linear_acceleration_covariancei<<5) & 0xff;
+      *(outbuffer + offset++) = (sig_linear_acceleration_covariancei>>3) & 0xff;
+      *(outbuffer + offset++) = (sig_linear_acceleration_covariancei>>11) & 0xff;
+      *(outbuffer + offset++) = ((exp_linear_acceleration_covariancei<<4) & 0xF0) | ((sig_linear_acceleration_covariancei>>19)&0x0F);
+      *(outbuffer + offset++) = (exp_linear_acceleration_covariancei>>4) & 0x7F;
+      if(this->linear_acceleration_covariance[i] < 0) *(outbuffer + offset -1) |= 0x80;
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->orientation.deserialize(inbuffer + offset);
+      unsigned char * orientation_covariance_val = (unsigned char *) this->orientation_covariance;
+      for( unsigned char i = 0; i < 9; i++){
+      unsigned long * val_orientation_covariancei = (unsigned long*) &(this->orientation_covariance[i]);
+      offset += 3;
+      *val_orientation_covariancei = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_orientation_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_orientation_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_orientation_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
+      unsigned long exp_orientation_covariancei = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_orientation_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      if(exp_orientation_covariancei !=0)
+        *val_orientation_covariancei |= ((exp_orientation_covariancei)-1023+127)<<23;
+      if( ((*(inbuffer+offset++)) & 0x80) > 0) this->orientation_covariance[i] = -this->orientation_covariance[i];
+      }
+      offset += this->angular_velocity.deserialize(inbuffer + offset);
+      unsigned char * angular_velocity_covariance_val = (unsigned char *) this->angular_velocity_covariance;
+      for( unsigned char i = 0; i < 9; i++){
+      unsigned long * val_angular_velocity_covariancei = (unsigned long*) &(this->angular_velocity_covariance[i]);
+      offset += 3;
+      *val_angular_velocity_covariancei = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_angular_velocity_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_angular_velocity_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_angular_velocity_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
+      unsigned long exp_angular_velocity_covariancei = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_angular_velocity_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      if(exp_angular_velocity_covariancei !=0)
+        *val_angular_velocity_covariancei |= ((exp_angular_velocity_covariancei)-1023+127)<<23;
+      if( ((*(inbuffer+offset++)) & 0x80) > 0) this->angular_velocity_covariance[i] = -this->angular_velocity_covariance[i];
+      }
+      offset += this->linear_acceleration.deserialize(inbuffer + offset);
+      unsigned char * linear_acceleration_covariance_val = (unsigned char *) this->linear_acceleration_covariance;
+      for( unsigned char i = 0; i < 9; i++){
+      unsigned long * val_linear_acceleration_covariancei = (unsigned long*) &(this->linear_acceleration_covariance[i]);
+      offset += 3;
+      *val_linear_acceleration_covariancei = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_linear_acceleration_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_linear_acceleration_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_linear_acceleration_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
+      unsigned long exp_linear_acceleration_covariancei = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_linear_acceleration_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      if(exp_linear_acceleration_covariancei !=0)
+        *val_linear_acceleration_covariancei |= ((exp_linear_acceleration_covariancei)-1023+127)<<23;
+      if( ((*(inbuffer+offset++)) & 0x80) > 0) this->linear_acceleration_covariance[i] = -this->linear_acceleration_covariance[i];
+      }
+     return offset;
+    }
+
+   virtual const char * getType(){ return "sensor_msgs/Imu"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/JointState.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,193 @@
+#ifndef ros_JointState_h
+#define ros_JointState_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/Header.h"
+
+namespace sensor_msgs
+{
+
+  class JointState : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      unsigned char name_length;
+      char* st_name;
+      char* * name;
+      unsigned char position_length;
+      float st_position;
+      float * position;
+      unsigned char velocity_length;
+      float st_velocity;
+      float * velocity;
+      unsigned char effort_length;
+      float st_effort;
+      float * effort;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = name_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( unsigned char i = 0; i < name_length; i++){
+      long * length_namei = (long *)(outbuffer + offset);
+      *length_namei = strlen( (const char*) this->name[i]);
+      offset += 4;
+      memcpy(outbuffer + offset, this->name[i], *length_namei);
+      offset += *length_namei;
+      }
+      *(outbuffer + offset++) = position_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( unsigned char i = 0; i < position_length; i++){
+      long * val_positioni = (long *) &(this->position[i]);
+      long exp_positioni = (((*val_positioni)>>23)&255);
+      if(exp_positioni != 0)
+        exp_positioni += 1023-127;
+      long sig_positioni = *val_positioni;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = (sig_positioni<<5) & 0xff;
+      *(outbuffer + offset++) = (sig_positioni>>3) & 0xff;
+      *(outbuffer + offset++) = (sig_positioni>>11) & 0xff;
+      *(outbuffer + offset++) = ((exp_positioni<<4) & 0xF0) | ((sig_positioni>>19)&0x0F);
+      *(outbuffer + offset++) = (exp_positioni>>4) & 0x7F;
+      if(this->position[i] < 0) *(outbuffer + offset -1) |= 0x80;
+      }
+      *(outbuffer + offset++) = velocity_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( unsigned char i = 0; i < velocity_length; i++){
+      long * val_velocityi = (long *) &(this->velocity[i]);
+      long exp_velocityi = (((*val_velocityi)>>23)&255);
+      if(exp_velocityi != 0)
+        exp_velocityi += 1023-127;
+      long sig_velocityi = *val_velocityi;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = (sig_velocityi<<5) & 0xff;
+      *(outbuffer + offset++) = (sig_velocityi>>3) & 0xff;
+      *(outbuffer + offset++) = (sig_velocityi>>11) & 0xff;
+      *(outbuffer + offset++) = ((exp_velocityi<<4) & 0xF0) | ((sig_velocityi>>19)&0x0F);
+      *(outbuffer + offset++) = (exp_velocityi>>4) & 0x7F;
+      if(this->velocity[i] < 0) *(outbuffer + offset -1) |= 0x80;
+      }
+      *(outbuffer + offset++) = effort_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( unsigned char i = 0; i < effort_length; i++){
+      long * val_efforti = (long *) &(this->effort[i]);
+      long exp_efforti = (((*val_efforti)>>23)&255);
+      if(exp_efforti != 0)
+        exp_efforti += 1023-127;
+      long sig_efforti = *val_efforti;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = (sig_efforti<<5) & 0xff;
+      *(outbuffer + offset++) = (sig_efforti>>3) & 0xff;
+      *(outbuffer + offset++) = (sig_efforti>>11) & 0xff;
+      *(outbuffer + offset++) = ((exp_efforti<<4) & 0xF0) | ((sig_efforti>>19)&0x0F);
+      *(outbuffer + offset++) = (exp_efforti>>4) & 0x7F;
+      if(this->effort[i] < 0) *(outbuffer + offset -1) |= 0x80;
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      unsigned char name_lengthT = *(inbuffer + offset++);
+      if(name_lengthT > name_length)
+        this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*));
+      offset += 3;
+      name_length = name_lengthT;
+      for( unsigned char i = 0; i < name_length; i++){
+      uint32_t length_st_name = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_st_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+           }
+      inbuffer[offset+length_st_name-1]=0;
+      this->st_name = (char *)(inbuffer + offset-1);
+      offset += length_st_name;
+        memcpy( &(this->name[i]), &(this->st_name), sizeof(char*));
+      }
+      unsigned char position_lengthT = *(inbuffer + offset++);
+      if(position_lengthT > position_length)
+        this->position = (float*)realloc(this->position, position_lengthT * sizeof(float));
+      offset += 3;
+      position_length = position_lengthT;
+      for( unsigned char i = 0; i < position_length; i++){
+      unsigned long * val_st_position = (unsigned long*) &(this->st_position);
+      offset += 3;
+      *val_st_position = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_st_position |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_st_position |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_st_position |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
+      unsigned long exp_st_position = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_st_position |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      if(exp_st_position !=0)
+        *val_st_position |= ((exp_st_position)-1023+127)<<23;
+      if( ((*(inbuffer+offset++)) & 0x80) > 0) this->st_position = -this->st_position;
+        memcpy( &(this->position[i]), &(this->st_position), sizeof(float));
+      }
+      unsigned char velocity_lengthT = *(inbuffer + offset++);
+      if(velocity_lengthT > velocity_length)
+        this->velocity = (float*)realloc(this->velocity, velocity_lengthT * sizeof(float));
+      offset += 3;
+      velocity_length = velocity_lengthT;
+      for( unsigned char i = 0; i < velocity_length; i++){
+      unsigned long * val_st_velocity = (unsigned long*) &(this->st_velocity);
+      offset += 3;
+      *val_st_velocity = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_st_velocity |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_st_velocity |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_st_velocity |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
+      unsigned long exp_st_velocity = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_st_velocity |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      if(exp_st_velocity !=0)
+        *val_st_velocity |= ((exp_st_velocity)-1023+127)<<23;
+      if( ((*(inbuffer+offset++)) & 0x80) > 0) this->st_velocity = -this->st_velocity;
+        memcpy( &(this->velocity[i]), &(this->st_velocity), sizeof(float));
+      }
+      unsigned char effort_lengthT = *(inbuffer + offset++);
+      if(effort_lengthT > effort_length)
+        this->effort = (float*)realloc(this->effort, effort_lengthT * sizeof(float));
+      offset += 3;
+      effort_length = effort_lengthT;
+      for( unsigned char i = 0; i < effort_length; i++){
+      unsigned long * val_st_effort = (unsigned long*) &(this->st_effort);
+      offset += 3;
+      *val_st_effort = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_st_effort |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_st_effort |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_st_effort |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
+      unsigned long exp_st_effort = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_st_effort |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      if(exp_st_effort !=0)
+        *val_st_effort |= ((exp_st_effort)-1023+127)<<23;
+      if( ((*(inbuffer+offset++)) & 0x80) > 0) this->st_effort = -this->st_effort;
+        memcpy( &(this->effort[i]), &(this->st_effort), sizeof(float));
+      }
+     return offset;
+    }
+
+   virtual const char * getType(){ return "sensor_msgs/JointState"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/LaserScan.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,267 @@
+#ifndef ros_LaserScan_h
+#define ros_LaserScan_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/Header.h"
+
+namespace sensor_msgs
+{
+
+  class LaserScan : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      float angle_min;
+      float angle_max;
+      float angle_increment;
+      float time_increment;
+      float scan_time;
+      float range_min;
+      float range_max;
+      unsigned char ranges_length;
+      float st_ranges;
+      float * ranges;
+      unsigned char intensities_length;
+      float st_intensities;
+      float * intensities;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      union {
+        float real;
+        unsigned long base;
+      } u_angle_min;
+      u_angle_min.real = this->angle_min;
+      *(outbuffer + offset + 0) = (u_angle_min.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_angle_min.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_angle_min.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_angle_min.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->angle_min);
+      union {
+        float real;
+        unsigned long base;
+      } u_angle_max;
+      u_angle_max.real = this->angle_max;
+      *(outbuffer + offset + 0) = (u_angle_max.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_angle_max.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_angle_max.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_angle_max.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->angle_max);
+      union {
+        float real;
+        unsigned long base;
+      } u_angle_increment;
+      u_angle_increment.real = this->angle_increment;
+      *(outbuffer + offset + 0) = (u_angle_increment.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_angle_increment.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_angle_increment.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_angle_increment.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->angle_increment);
+      union {
+        float real;
+        unsigned long base;
+      } u_time_increment;
+      u_time_increment.real = this->time_increment;
+      *(outbuffer + offset + 0) = (u_time_increment.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_time_increment.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_time_increment.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_time_increment.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->time_increment);
+      union {
+        float real;
+        unsigned long base;
+      } u_scan_time;
+      u_scan_time.real = this->scan_time;
+      *(outbuffer + offset + 0) = (u_scan_time.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_scan_time.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_scan_time.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_scan_time.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->scan_time);
+      union {
+        float real;
+        unsigned long base;
+      } u_range_min;
+      u_range_min.real = this->range_min;
+      *(outbuffer + offset + 0) = (u_range_min.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_range_min.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_range_min.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_range_min.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->range_min);
+      union {
+        float real;
+        unsigned long base;
+      } u_range_max;
+      u_range_max.real = this->range_max;
+      *(outbuffer + offset + 0) = (u_range_max.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_range_max.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_range_max.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_range_max.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->range_max);
+      *(outbuffer + offset++) = ranges_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( unsigned char i = 0; i < ranges_length; i++){
+      union {
+        float real;
+        unsigned long base;
+      } u_rangesi;
+      u_rangesi.real = this->ranges[i];
+      *(outbuffer + offset + 0) = (u_rangesi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_rangesi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_rangesi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_rangesi.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->ranges[i]);
+      }
+      *(outbuffer + offset++) = intensities_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( unsigned char i = 0; i < intensities_length; i++){
+      union {
+        float real;
+        unsigned long base;
+      } u_intensitiesi;
+      u_intensitiesi.real = this->intensities[i];
+      *(outbuffer + offset + 0) = (u_intensitiesi.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_intensitiesi.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_intensitiesi.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_intensitiesi.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->intensities[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      union {
+        float real;
+        unsigned long base;
+      } u_angle_min;
+      u_angle_min.base = 0;
+      u_angle_min.base |= ((typeof(u_angle_min.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_angle_min.base |= ((typeof(u_angle_min.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_angle_min.base |= ((typeof(u_angle_min.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_angle_min.base |= ((typeof(u_angle_min.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->angle_min = u_angle_min.real;
+      offset += sizeof(this->angle_min);
+      union {
+        float real;
+        unsigned long base;
+      } u_angle_max;
+      u_angle_max.base = 0;
+      u_angle_max.base |= ((typeof(u_angle_max.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_angle_max.base |= ((typeof(u_angle_max.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_angle_max.base |= ((typeof(u_angle_max.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_angle_max.base |= ((typeof(u_angle_max.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->angle_max = u_angle_max.real;
+      offset += sizeof(this->angle_max);
+      union {
+        float real;
+        unsigned long base;
+      } u_angle_increment;
+      u_angle_increment.base = 0;
+      u_angle_increment.base |= ((typeof(u_angle_increment.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_angle_increment.base |= ((typeof(u_angle_increment.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_angle_increment.base |= ((typeof(u_angle_increment.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_angle_increment.base |= ((typeof(u_angle_increment.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->angle_increment = u_angle_increment.real;
+      offset += sizeof(this->angle_increment);
+      union {
+        float real;
+        unsigned long base;
+      } u_time_increment;
+      u_time_increment.base = 0;
+      u_time_increment.base |= ((typeof(u_time_increment.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_time_increment.base |= ((typeof(u_time_increment.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_time_increment.base |= ((typeof(u_time_increment.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_time_increment.base |= ((typeof(u_time_increment.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->time_increment = u_time_increment.real;
+      offset += sizeof(this->time_increment);
+      union {
+        float real;
+        unsigned long base;
+      } u_scan_time;
+      u_scan_time.base = 0;
+      u_scan_time.base |= ((typeof(u_scan_time.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_scan_time.base |= ((typeof(u_scan_time.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_scan_time.base |= ((typeof(u_scan_time.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_scan_time.base |= ((typeof(u_scan_time.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->scan_time = u_scan_time.real;
+      offset += sizeof(this->scan_time);
+      union {
+        float real;
+        unsigned long base;
+      } u_range_min;
+      u_range_min.base = 0;
+      u_range_min.base |= ((typeof(u_range_min.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_range_min.base |= ((typeof(u_range_min.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_range_min.base |= ((typeof(u_range_min.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_range_min.base |= ((typeof(u_range_min.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->range_min = u_range_min.real;
+      offset += sizeof(this->range_min);
+      union {
+        float real;
+        unsigned long base;
+      } u_range_max;
+      u_range_max.base = 0;
+      u_range_max.base |= ((typeof(u_range_max.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_range_max.base |= ((typeof(u_range_max.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_range_max.base |= ((typeof(u_range_max.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_range_max.base |= ((typeof(u_range_max.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->range_max = u_range_max.real;
+      offset += sizeof(this->range_max);
+      unsigned char ranges_lengthT = *(inbuffer + offset++);
+      if(ranges_lengthT > ranges_length)
+        this->ranges = (float*)realloc(this->ranges, ranges_lengthT * sizeof(float));
+      offset += 3;
+      ranges_length = ranges_lengthT;
+      for( unsigned char i = 0; i < ranges_length; i++){
+      union {
+        float real;
+        unsigned long base;
+      } u_st_ranges;
+      u_st_ranges.base = 0;
+      u_st_ranges.base |= ((typeof(u_st_ranges.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_ranges.base |= ((typeof(u_st_ranges.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_ranges.base |= ((typeof(u_st_ranges.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_ranges.base |= ((typeof(u_st_ranges.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->st_ranges = u_st_ranges.real;
+      offset += sizeof(this->st_ranges);
+        memcpy( &(this->ranges[i]), &(this->st_ranges), sizeof(float));
+      }
+      unsigned char intensities_lengthT = *(inbuffer + offset++);
+      if(intensities_lengthT > intensities_length)
+        this->intensities = (float*)realloc(this->intensities, intensities_lengthT * sizeof(float));
+      offset += 3;
+      intensities_length = intensities_lengthT;
+      for( unsigned char i = 0; i < intensities_length; i++){
+      union {
+        float real;
+        unsigned long base;
+      } u_st_intensities;
+      u_st_intensities.base = 0;
+      u_st_intensities.base |= ((typeof(u_st_intensities.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_st_intensities.base |= ((typeof(u_st_intensities.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_st_intensities.base |= ((typeof(u_st_intensities.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_st_intensities.base |= ((typeof(u_st_intensities.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->st_intensities = u_st_intensities.real;
+      offset += sizeof(this->st_intensities);
+        memcpy( &(this->intensities[i]), &(this->st_intensities), sizeof(float));
+      }
+     return offset;
+    }
+
+   virtual const char * getType(){ return "sensor_msgs/LaserScan"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/NavSatFix.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,171 @@
+#ifndef ros_NavSatFix_h
+#define ros_NavSatFix_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/Header.h"
+#include "sensor_msgs/NavSatStatus.h"
+
+namespace sensor_msgs
+{
+
+  class NavSatFix : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      sensor_msgs::NavSatStatus status;
+      float latitude;
+      float longitude;
+      float altitude;
+      float position_covariance[9];
+      unsigned char position_covariance_type;
+      enum { COVARIANCE_TYPE_UNKNOWN = 0 };
+      enum { COVARIANCE_TYPE_APPROXIMATED = 1 };
+      enum { COVARIANCE_TYPE_DIAGONAL_KNOWN = 2 };
+      enum { COVARIANCE_TYPE_KNOWN = 3 };
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      offset += this->status.serialize(outbuffer + offset);
+      long * val_latitude = (long *) &(this->latitude);
+      long exp_latitude = (((*val_latitude)>>23)&255);
+      if(exp_latitude != 0)
+        exp_latitude += 1023-127;
+      long sig_latitude = *val_latitude;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = (sig_latitude<<5) & 0xff;
+      *(outbuffer + offset++) = (sig_latitude>>3) & 0xff;
+      *(outbuffer + offset++) = (sig_latitude>>11) & 0xff;
+      *(outbuffer + offset++) = ((exp_latitude<<4) & 0xF0) | ((sig_latitude>>19)&0x0F);
+      *(outbuffer + offset++) = (exp_latitude>>4) & 0x7F;
+      if(this->latitude < 0) *(outbuffer + offset -1) |= 0x80;
+      long * val_longitude = (long *) &(this->longitude);
+      long exp_longitude = (((*val_longitude)>>23)&255);
+      if(exp_longitude != 0)
+        exp_longitude += 1023-127;
+      long sig_longitude = *val_longitude;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = (sig_longitude<<5) & 0xff;
+      *(outbuffer + offset++) = (sig_longitude>>3) & 0xff;
+      *(outbuffer + offset++) = (sig_longitude>>11) & 0xff;
+      *(outbuffer + offset++) = ((exp_longitude<<4) & 0xF0) | ((sig_longitude>>19)&0x0F);
+      *(outbuffer + offset++) = (exp_longitude>>4) & 0x7F;
+      if(this->longitude < 0) *(outbuffer + offset -1) |= 0x80;
+      long * val_altitude = (long *) &(this->altitude);
+      long exp_altitude = (((*val_altitude)>>23)&255);
+      if(exp_altitude != 0)
+        exp_altitude += 1023-127;
+      long sig_altitude = *val_altitude;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = (sig_altitude<<5) & 0xff;
+      *(outbuffer + offset++) = (sig_altitude>>3) & 0xff;
+      *(outbuffer + offset++) = (sig_altitude>>11) & 0xff;
+      *(outbuffer + offset++) = ((exp_altitude<<4) & 0xF0) | ((sig_altitude>>19)&0x0F);
+      *(outbuffer + offset++) = (exp_altitude>>4) & 0x7F;
+      if(this->altitude < 0) *(outbuffer + offset -1) |= 0x80;
+      unsigned char * position_covariance_val = (unsigned char *) this->position_covariance;
+      for( unsigned char i = 0; i < 9; i++){
+      long * val_position_covariancei = (long *) &(this->position_covariance[i]);
+      long exp_position_covariancei = (((*val_position_covariancei)>>23)&255);
+      if(exp_position_covariancei != 0)
+        exp_position_covariancei += 1023-127;
+      long sig_position_covariancei = *val_position_covariancei;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = (sig_position_covariancei<<5) & 0xff;
+      *(outbuffer + offset++) = (sig_position_covariancei>>3) & 0xff;
+      *(outbuffer + offset++) = (sig_position_covariancei>>11) & 0xff;
+      *(outbuffer + offset++) = ((exp_position_covariancei<<4) & 0xF0) | ((sig_position_covariancei>>19)&0x0F);
+      *(outbuffer + offset++) = (exp_position_covariancei>>4) & 0x7F;
+      if(this->position_covariance[i] < 0) *(outbuffer + offset -1) |= 0x80;
+      }
+      union {
+        unsigned char real;
+        unsigned char base;
+      } u_position_covariance_type;
+      u_position_covariance_type.real = this->position_covariance_type;
+      *(outbuffer + offset + 0) = (u_position_covariance_type.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->position_covariance_type);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      offset += this->status.deserialize(inbuffer + offset);
+      unsigned long * val_latitude = (unsigned long*) &(this->latitude);
+      offset += 3;
+      *val_latitude = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_latitude |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_latitude |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_latitude |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
+      unsigned long exp_latitude = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_latitude |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      if(exp_latitude !=0)
+        *val_latitude |= ((exp_latitude)-1023+127)<<23;
+      if( ((*(inbuffer+offset++)) & 0x80) > 0) this->latitude = -this->latitude;
+      unsigned long * val_longitude = (unsigned long*) &(this->longitude);
+      offset += 3;
+      *val_longitude = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_longitude |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_longitude |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_longitude |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
+      unsigned long exp_longitude = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_longitude |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      if(exp_longitude !=0)
+        *val_longitude |= ((exp_longitude)-1023+127)<<23;
+      if( ((*(inbuffer+offset++)) & 0x80) > 0) this->longitude = -this->longitude;
+      unsigned long * val_altitude = (unsigned long*) &(this->altitude);
+      offset += 3;
+      *val_altitude = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_altitude |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_altitude |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_altitude |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
+      unsigned long exp_altitude = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_altitude |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      if(exp_altitude !=0)
+        *val_altitude |= ((exp_altitude)-1023+127)<<23;
+      if( ((*(inbuffer+offset++)) & 0x80) > 0) this->altitude = -this->altitude;
+      unsigned char * position_covariance_val = (unsigned char *) this->position_covariance;
+      for( unsigned char i = 0; i < 9; i++){
+      unsigned long * val_position_covariancei = (unsigned long*) &(this->position_covariance[i]);
+      offset += 3;
+      *val_position_covariancei = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_position_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_position_covariancei |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_position_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
+      unsigned long exp_position_covariancei = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_position_covariancei |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      if(exp_position_covariancei !=0)
+        *val_position_covariancei |= ((exp_position_covariancei)-1023+127)<<23;
+      if( ((*(inbuffer+offset++)) & 0x80) > 0) this->position_covariance[i] = -this->position_covariance[i];
+      }
+      union {
+        unsigned char real;
+        unsigned char base;
+      } u_position_covariance_type;
+      u_position_covariance_type.base = 0;
+      u_position_covariance_type.base |= ((typeof(u_position_covariance_type.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->position_covariance_type = u_position_covariance_type.real;
+      offset += sizeof(this->position_covariance_type);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "sensor_msgs/NavSatFix"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/NavSatStatus.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,75 @@
+#ifndef ros_NavSatStatus_h
+#define ros_NavSatStatus_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace sensor_msgs
+{
+
+  class NavSatStatus : public ros::Msg
+  {
+    public:
+      signed char status;
+      unsigned short service;
+      enum { STATUS_NO_FIX = -1 };
+      enum { STATUS_FIX = 0 };
+      enum { STATUS_SBAS_FIX = 1 };
+      enum { STATUS_GBAS_FIX = 2 };
+      enum { SERVICE_GPS = 1 };
+      enum { SERVICE_GLONASS = 2 };
+      enum { SERVICE_COMPASS = 4 };
+      enum { SERVICE_GALILEO = 8 };
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      union {
+        signed char real;
+        unsigned char base;
+      } u_status;
+      u_status.real = this->status;
+      *(outbuffer + offset + 0) = (u_status.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->status);
+      union {
+        unsigned short real;
+        unsigned short base;
+      } u_service;
+      u_service.real = this->service;
+      *(outbuffer + offset + 0) = (u_service.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_service.base >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->service);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        signed char real;
+        unsigned char base;
+      } u_status;
+      u_status.base = 0;
+      u_status.base |= ((typeof(u_status.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->status = u_status.real;
+      offset += sizeof(this->status);
+      union {
+        unsigned short real;
+        unsigned short base;
+      } u_service;
+      u_service.base = 0;
+      u_service.base |= ((typeof(u_service.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_service.base |= ((typeof(u_service.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->service = u_service.real;
+      offset += sizeof(this->service);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "sensor_msgs/NavSatStatus"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/PointCloud.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,77 @@
+#ifndef ros_PointCloud_h
+#define ros_PointCloud_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/Header.h"
+#include "geometry_msgs/Point32.h"
+#include "sensor_msgs/ChannelFloat32.h"
+
+namespace sensor_msgs
+{
+
+  class PointCloud : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      unsigned char points_length;
+      geometry_msgs::Point32 st_points;
+      geometry_msgs::Point32 * points;
+      unsigned char channels_length;
+      sensor_msgs::ChannelFloat32 st_channels;
+      sensor_msgs::ChannelFloat32 * channels;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      *(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);
+      }
+      *(outbuffer + offset++) = channels_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( unsigned char i = 0; i < channels_length; i++){
+      offset += this->channels[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      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));
+      }
+      unsigned char channels_lengthT = *(inbuffer + offset++);
+      if(channels_lengthT > channels_length)
+        this->channels = (sensor_msgs::ChannelFloat32*)realloc(this->channels, channels_lengthT * sizeof(sensor_msgs::ChannelFloat32));
+      offset += 3;
+      channels_length = channels_lengthT;
+      for( unsigned char i = 0; i < channels_length; i++){
+      offset += this->st_channels.deserialize(inbuffer + offset);
+        memcpy( &(this->channels[i]), &(this->st_channels), sizeof(sensor_msgs::ChannelFloat32));
+      }
+     return offset;
+    }
+
+   virtual const char * getType(){ return "sensor_msgs/PointCloud"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/PointCloud2.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,209 @@
+#ifndef ros_PointCloud2_h
+#define ros_PointCloud2_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/Header.h"
+#include "sensor_msgs/PointField.h"
+
+namespace sensor_msgs
+{
+
+  class PointCloud2 : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      unsigned long height;
+      unsigned long width;
+      unsigned char fields_length;
+      sensor_msgs::PointField st_fields;
+      sensor_msgs::PointField * fields;
+      bool is_bigendian;
+      unsigned long point_step;
+      unsigned long row_step;
+      unsigned char data_length;
+      unsigned char st_data;
+      unsigned char * data;
+      bool is_dense;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_height;
+      u_height.real = this->height;
+      *(outbuffer + offset + 0) = (u_height.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_height.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_height.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_height.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->height);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_width;
+      u_width.real = this->width;
+      *(outbuffer + offset + 0) = (u_width.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_width.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_width.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_width.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->width);
+      *(outbuffer + offset++) = fields_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( unsigned char i = 0; i < fields_length; i++){
+      offset += this->fields[i].serialize(outbuffer + offset);
+      }
+      union {
+        bool real;
+        unsigned char base;
+      } u_is_bigendian;
+      u_is_bigendian.real = this->is_bigendian;
+      *(outbuffer + offset + 0) = (u_is_bigendian.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->is_bigendian);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_point_step;
+      u_point_step.real = this->point_step;
+      *(outbuffer + offset + 0) = (u_point_step.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_point_step.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_point_step.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_point_step.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->point_step);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_row_step;
+      u_row_step.real = this->row_step;
+      *(outbuffer + offset + 0) = (u_row_step.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_row_step.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_row_step.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_row_step.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->row_step);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( unsigned char i = 0; i < data_length; i++){
+      union {
+        unsigned char real;
+        unsigned char base;
+      } u_datai;
+      u_datai.real = this->data[i];
+      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      union {
+        bool real;
+        unsigned char base;
+      } u_is_dense;
+      u_is_dense.real = this->is_dense;
+      *(outbuffer + offset + 0) = (u_is_dense.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->is_dense);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_height;
+      u_height.base = 0;
+      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->height = u_height.real;
+      offset += sizeof(this->height);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_width;
+      u_width.base = 0;
+      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->width = u_width.real;
+      offset += sizeof(this->width);
+      unsigned char fields_lengthT = *(inbuffer + offset++);
+      if(fields_lengthT > fields_length)
+        this->fields = (sensor_msgs::PointField*)realloc(this->fields, fields_lengthT * sizeof(sensor_msgs::PointField));
+      offset += 3;
+      fields_length = fields_lengthT;
+      for( unsigned char i = 0; i < fields_length; i++){
+      offset += this->st_fields.deserialize(inbuffer + offset);
+        memcpy( &(this->fields[i]), &(this->st_fields), sizeof(sensor_msgs::PointField));
+      }
+      union {
+        bool real;
+        unsigned char base;
+      } u_is_bigendian;
+      u_is_bigendian.base = 0;
+      u_is_bigendian.base |= ((typeof(u_is_bigendian.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->is_bigendian = u_is_bigendian.real;
+      offset += sizeof(this->is_bigendian);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_point_step;
+      u_point_step.base = 0;
+      u_point_step.base |= ((typeof(u_point_step.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_point_step.base |= ((typeof(u_point_step.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_point_step.base |= ((typeof(u_point_step.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_point_step.base |= ((typeof(u_point_step.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->point_step = u_point_step.real;
+      offset += sizeof(this->point_step);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_row_step;
+      u_row_step.base = 0;
+      u_row_step.base |= ((typeof(u_row_step.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_row_step.base |= ((typeof(u_row_step.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_row_step.base |= ((typeof(u_row_step.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_row_step.base |= ((typeof(u_row_step.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->row_step = u_row_step.real;
+      offset += sizeof(this->row_step);
+      unsigned char data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (unsigned char*)realloc(this->data, data_lengthT * sizeof(unsigned char));
+      offset += 3;
+      data_length = data_lengthT;
+      for( unsigned char i = 0; i < data_length; i++){
+      union {
+        unsigned char real;
+        unsigned char base;
+      } u_st_data;
+      u_st_data.base = 0;
+      u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->st_data = u_st_data.real;
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(unsigned char));
+      }
+      union {
+        bool real;
+        unsigned char base;
+      } u_is_dense;
+      u_is_dense.base = 0;
+      u_is_dense.base |= ((typeof(u_is_dense.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->is_dense = u_is_dense.real;
+      offset += sizeof(this->is_dense);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "sensor_msgs/PointCloud2"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/PointField.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,115 @@
+#ifndef ros_PointField_h
+#define ros_PointField_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace sensor_msgs
+{
+
+  class PointField : public ros::Msg
+  {
+    public:
+      char * name;
+      unsigned long offset;
+      unsigned char datatype;
+      unsigned long count;
+      enum { INT8 = 1 };
+      enum { UINT8 = 2 };
+      enum { INT16 = 3 };
+      enum { UINT16 = 4 };
+      enum { INT32 = 5 };
+      enum { UINT32 = 6 };
+      enum { FLOAT32 = 7 };
+      enum { FLOAT64 = 8 };
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      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;
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_offset;
+      u_offset.real = this->offset;
+      *(outbuffer + offset + 0) = (u_offset.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_offset.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_offset.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_offset.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->offset);
+      union {
+        unsigned char real;
+        unsigned char base;
+      } u_datatype;
+      u_datatype.real = this->datatype;
+      *(outbuffer + offset + 0) = (u_datatype.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->datatype);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_count;
+      u_count.real = this->count;
+      *(outbuffer + offset + 0) = (u_count.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_count.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_count.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_count.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->count);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_name = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_name; ++k){
+          inbuffer[k-1]=inbuffer[k];
+           }
+      inbuffer[offset+length_name-1]=0;
+      this->name = (char *)(inbuffer + offset-1);
+      offset += length_name;
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_offset;
+      u_offset.base = 0;
+      u_offset.base |= ((typeof(u_offset.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_offset.base |= ((typeof(u_offset.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_offset.base |= ((typeof(u_offset.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_offset.base |= ((typeof(u_offset.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->offset = u_offset.real;
+      offset += sizeof(this->offset);
+      union {
+        unsigned char real;
+        unsigned char base;
+      } u_datatype;
+      u_datatype.base = 0;
+      u_datatype.base |= ((typeof(u_datatype.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->datatype = u_datatype.real;
+      offset += sizeof(this->datatype);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_count;
+      u_count.base = 0;
+      u_count.base |= ((typeof(u_count.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_count.base |= ((typeof(u_count.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_count.base |= ((typeof(u_count.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_count.base |= ((typeof(u_count.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->count = u_count.real;
+      offset += sizeof(this->count);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "sensor_msgs/PointField"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/Range.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,143 @@
+#ifndef ros_Range_h
+#define ros_Range_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/Header.h"
+
+namespace sensor_msgs
+{
+
+  class Range : public ros::Msg
+  {
+    public:
+      std_msgs::Header header;
+      unsigned char radiation_type;
+      float field_of_view;
+      float min_range;
+      float max_range;
+      float range;
+      enum { ULTRASOUND = 0 };
+      enum { INFRARED = 1 };
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->header.serialize(outbuffer + offset);
+      union {
+        unsigned char real;
+        unsigned char base;
+      } u_radiation_type;
+      u_radiation_type.real = this->radiation_type;
+      *(outbuffer + offset + 0) = (u_radiation_type.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->radiation_type);
+      union {
+        float real;
+        unsigned long base;
+      } u_field_of_view;
+      u_field_of_view.real = this->field_of_view;
+      *(outbuffer + offset + 0) = (u_field_of_view.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_field_of_view.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_field_of_view.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_field_of_view.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->field_of_view);
+      union {
+        float real;
+        unsigned long base;
+      } u_min_range;
+      u_min_range.real = this->min_range;
+      *(outbuffer + offset + 0) = (u_min_range.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_min_range.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_min_range.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_min_range.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->min_range);
+      union {
+        float real;
+        unsigned long base;
+      } u_max_range;
+      u_max_range.real = this->max_range;
+      *(outbuffer + offset + 0) = (u_max_range.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_max_range.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_max_range.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_max_range.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->max_range);
+      union {
+        float real;
+        unsigned long base;
+      } u_range;
+      u_range.real = this->range;
+      *(outbuffer + offset + 0) = (u_range.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_range.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_range.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_range.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->range);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->header.deserialize(inbuffer + offset);
+      union {
+        unsigned char real;
+        unsigned char base;
+      } u_radiation_type;
+      u_radiation_type.base = 0;
+      u_radiation_type.base |= ((typeof(u_radiation_type.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->radiation_type = u_radiation_type.real;
+      offset += sizeof(this->radiation_type);
+      union {
+        float real;
+        unsigned long base;
+      } u_field_of_view;
+      u_field_of_view.base = 0;
+      u_field_of_view.base |= ((typeof(u_field_of_view.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_field_of_view.base |= ((typeof(u_field_of_view.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_field_of_view.base |= ((typeof(u_field_of_view.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_field_of_view.base |= ((typeof(u_field_of_view.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->field_of_view = u_field_of_view.real;
+      offset += sizeof(this->field_of_view);
+      union {
+        float real;
+        unsigned long base;
+      } u_min_range;
+      u_min_range.base = 0;
+      u_min_range.base |= ((typeof(u_min_range.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_min_range.base |= ((typeof(u_min_range.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_min_range.base |= ((typeof(u_min_range.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_min_range.base |= ((typeof(u_min_range.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->min_range = u_min_range.real;
+      offset += sizeof(this->min_range);
+      union {
+        float real;
+        unsigned long base;
+      } u_max_range;
+      u_max_range.base = 0;
+      u_max_range.base |= ((typeof(u_max_range.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_max_range.base |= ((typeof(u_max_range.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_max_range.base |= ((typeof(u_max_range.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_max_range.base |= ((typeof(u_max_range.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->max_range = u_max_range.real;
+      offset += sizeof(this->max_range);
+      union {
+        float real;
+        unsigned long base;
+      } u_range;
+      u_range.base = 0;
+      u_range.base |= ((typeof(u_range.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_range.base |= ((typeof(u_range.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_range.base |= ((typeof(u_range.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_range.base |= ((typeof(u_range.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->range = u_range.real;
+      offset += sizeof(this->range);
+     return offset;
+    }
+
+    virtual const char * getType(){ return "sensor_msgs/Range"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/RegionOfInterest.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,137 @@
+#ifndef ros_RegionOfInterest_h
+#define ros_RegionOfInterest_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace sensor_msgs
+{
+
+  class RegionOfInterest : public ros::Msg
+  {
+    public:
+      unsigned long x_offset;
+      unsigned long y_offset;
+      unsigned long height;
+      unsigned long width;
+      bool do_rectify;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_x_offset;
+      u_x_offset.real = this->x_offset;
+      *(outbuffer + offset + 0) = (u_x_offset.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_x_offset.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_x_offset.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_x_offset.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->x_offset);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_y_offset;
+      u_y_offset.real = this->y_offset;
+      *(outbuffer + offset + 0) = (u_y_offset.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_y_offset.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_y_offset.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_y_offset.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->y_offset);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_height;
+      u_height.real = this->height;
+      *(outbuffer + offset + 0) = (u_height.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_height.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_height.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_height.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->height);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_width;
+      u_width.real = this->width;
+      *(outbuffer + offset + 0) = (u_width.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_width.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_width.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_width.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->width);
+      union {
+        bool real;
+        unsigned char base;
+      } u_do_rectify;
+      u_do_rectify.real = this->do_rectify;
+      *(outbuffer + offset + 0) = (u_do_rectify.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->do_rectify);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_x_offset;
+      u_x_offset.base = 0;
+      u_x_offset.base |= ((typeof(u_x_offset.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_x_offset.base |= ((typeof(u_x_offset.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_x_offset.base |= ((typeof(u_x_offset.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_x_offset.base |= ((typeof(u_x_offset.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->x_offset = u_x_offset.real;
+      offset += sizeof(this->x_offset);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_y_offset;
+      u_y_offset.base = 0;
+      u_y_offset.base |= ((typeof(u_y_offset.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_y_offset.base |= ((typeof(u_y_offset.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_y_offset.base |= ((typeof(u_y_offset.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_y_offset.base |= ((typeof(u_y_offset.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->y_offset = u_y_offset.real;
+      offset += sizeof(this->y_offset);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_height;
+      u_height.base = 0;
+      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->height = u_height.real;
+      offset += sizeof(this->height);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_width;
+      u_width.base = 0;
+      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->width = u_width.real;
+      offset += sizeof(this->width);
+      union {
+        bool real;
+        unsigned char base;
+      } u_do_rectify;
+      u_do_rectify.base = 0;
+      u_do_rectify.base |= ((typeof(u_do_rectify.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->do_rectify = u_do_rectify.real;
+      offset += sizeof(this->do_rectify);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "sensor_msgs/RegionOfInterest"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/sensor_msgs/SetCameraInfo.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,88 @@
+#ifndef ros_SERVICE_SetCameraInfo_h
+#define ros_SERVICE_SetCameraInfo_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "sensor_msgs/CameraInfo.h"
+
+namespace sensor_msgs
+{
+
+static const char SETCAMERAINFO[] = "sensor_msgs/SetCameraInfo";
+
+  class SetCameraInfoRequest : public ros::Msg
+  {
+    public:
+      sensor_msgs::CameraInfo camera_info;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->camera_info.serialize(outbuffer + offset);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->camera_info.deserialize(inbuffer + offset);
+     return offset;
+    }
+
+   virtual const char * getType(){ return SETCAMERAINFO; };
+
+  };
+
+  class SetCameraInfoResponse : public ros::Msg
+  {
+    public:
+      bool success;
+      char * status_message;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      union {
+        bool real;
+        unsigned char base;
+      } u_success;
+      u_success.real = this->success;
+      *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->success);
+      long * length_status_message = (long *)(outbuffer + offset);
+      *length_status_message = strlen( (const char*) this->status_message);
+      offset += 4;
+      memcpy(outbuffer + offset, this->status_message, *length_status_message);
+      offset += *length_status_message;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        bool real;
+        unsigned char base;
+      } u_success;
+      u_success.base = 0;
+      u_success.base |= ((typeof(u_success.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->success = u_success.real;
+      offset += sizeof(this->success);
+      uint32_t length_status_message = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_status_message; ++k){
+          inbuffer[k-1]=inbuffer[k];
+           }
+      inbuffer[offset+length_status_message-1]=0;
+      this->status_message = (char *)(inbuffer + offset-1);
+      offset += length_status_message;
+     return offset;
+    }
+
+   virtual const char * getType(){ return SETCAMERAINFO; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Bool.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,49 @@
+#ifndef ros_Bool_h
+#define ros_Bool_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace std_msgs
+{
+
+  class Bool : public ros::Msg
+  {
+    public:
+      bool data;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      union {
+        bool real;
+        unsigned char base;
+      } u_data;
+      u_data.real = this->data;
+      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        bool real;
+        unsigned char base;
+      } u_data;
+      u_data.base = 0;
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->data = u_data.real;
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/Bool"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Byte.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,49 @@
+#ifndef ros_Byte_h
+#define ros_Byte_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace std_msgs
+{
+
+  class Byte : public ros::Msg
+  {
+    public:
+      unsigned char data;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      union {
+        unsigned char real;
+        unsigned char base;
+      } u_data;
+      u_data.real = this->data;
+      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        unsigned char real;
+        unsigned char base;
+      } u_data;
+      u_data.base = 0;
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->data = u_data.real;
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "std_msgs/Byte"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/ByteMultiArray.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,69 @@
+#ifndef ros_ByteMultiArray_h
+#define ros_ByteMultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class ByteMultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      unsigned char data_length;
+      unsigned char st_data;
+      unsigned char * 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 {
+        unsigned char real;
+        unsigned char base;
+      } u_datai;
+      u_datai.real = this->data[i];
+      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      unsigned char data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (unsigned char*)realloc(this->data, data_lengthT * sizeof(unsigned char));
+      offset += 3;
+      data_length = data_lengthT;
+      for( unsigned char i = 0; i < data_length; i++){
+      union {
+        unsigned char real;
+        unsigned char base;
+      } u_st_data;
+      u_st_data.base = 0;
+      u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->st_data = u_st_data.real;
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(unsigned char));
+      }
+     return offset;
+    }
+
+   virtual const char * getType(){ return "std_msgs/ByteMultiArray"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Char.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,49 @@
+#ifndef ros_Char_h
+#define ros_Char_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace std_msgs
+{
+
+  class Char : public ros::Msg
+  {
+    public:
+      char data;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      union {
+        char real;
+        unsigned char base;
+      } u_data;
+      u_data.real = this->data;
+      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        char real;
+        unsigned char base;
+      } u_data;
+      u_data.base = 0;
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->data = u_data.real;
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "std_msgs/Char"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/ColorRGBA.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,121 @@
+#ifndef ros_ColorRGBA_h
+#define ros_ColorRGBA_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace std_msgs
+{
+
+  class ColorRGBA : public ros::Msg
+  {
+    public:
+      float r;
+      float g;
+      float b;
+      float a;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      union {
+        float real;
+        unsigned long base;
+      } u_r;
+      u_r.real = this->r;
+      *(outbuffer + offset + 0) = (u_r.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_r.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_r.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_r.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->r);
+      union {
+        float real;
+        unsigned long base;
+      } u_g;
+      u_g.real = this->g;
+      *(outbuffer + offset + 0) = (u_g.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_g.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_g.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_g.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->g);
+      union {
+        float real;
+        unsigned long base;
+      } u_b;
+      u_b.real = this->b;
+      *(outbuffer + offset + 0) = (u_b.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_b.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_b.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_b.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->b);
+      union {
+        float real;
+        unsigned long base;
+      } u_a;
+      u_a.real = this->a;
+      *(outbuffer + offset + 0) = (u_a.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_a.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_a.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_a.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->a);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        float real;
+        unsigned long base;
+      } u_r;
+      u_r.base = 0;
+      u_r.base |= ((typeof(u_r.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_r.base |= ((typeof(u_r.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_r.base |= ((typeof(u_r.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_r.base |= ((typeof(u_r.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->r = u_r.real;
+      offset += sizeof(this->r);
+      union {
+        float real;
+        unsigned long base;
+      } u_g;
+      u_g.base = 0;
+      u_g.base |= ((typeof(u_g.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_g.base |= ((typeof(u_g.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_g.base |= ((typeof(u_g.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_g.base |= ((typeof(u_g.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->g = u_g.real;
+      offset += sizeof(this->g);
+      union {
+        float real;
+        unsigned long base;
+      } u_b;
+      u_b.base = 0;
+      u_b.base |= ((typeof(u_b.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_b.base |= ((typeof(u_b.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_b.base |= ((typeof(u_b.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_b.base |= ((typeof(u_b.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->b = u_b.real;
+      offset += sizeof(this->b);
+      union {
+        float real;
+        unsigned long base;
+      } u_a;
+      u_a.base = 0;
+      u_a.base |= ((typeof(u_a.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_a.base |= ((typeof(u_a.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_a.base |= ((typeof(u_a.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_a.base |= ((typeof(u_a.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->a = u_a.real;
+      offset += sizeof(this->a);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "std_msgs/ColorRGBA"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Duration.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,77 @@
+#ifndef ros_Duration_h
+#define ros_Duration_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "ros/duration.h"
+
+namespace std_msgs
+{
+
+  class Duration : public ros::Msg
+  {
+    public:
+      ros::Duration data;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_sec;
+      u_sec.real = this->data.sec;
+      *(outbuffer + offset + 0) = (u_sec.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_sec.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_sec.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_sec.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data.sec);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_nsec;
+      u_nsec.real = this->data.nsec;
+      *(outbuffer + offset + 0) = (u_nsec.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_nsec.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_nsec.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_nsec.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data.nsec);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_sec;
+      u_sec.base = 0;
+      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->data.sec = u_sec.real;
+      offset += sizeof(this->data.sec);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_nsec;
+      u_nsec.base = 0;
+      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->data.nsec = u_nsec.real;
+      offset += sizeof(this->data.nsec);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "std_msgs/Duration"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Empty.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,31 @@
+#ifndef ros_Empty_h
+#define ros_Empty_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace std_msgs {
+
+class Empty : public ros::Msg {
+public:
+
+    virtual int serialize(unsigned char *outbuffer) {
+        int offset = 0;
+        return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer) {
+        int offset = 0;
+        return offset;
+    }
+
+    virtual const char * getType() {
+        return "std_msgs/Empty";
+    };
+
+};
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Float32.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,55 @@
+#ifndef ros_Float32_h
+#define ros_Float32_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace std_msgs
+{
+
+  class Float32 : public ros::Msg
+  {
+    public:
+      float data;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      union {
+        float real;
+        unsigned long base;
+      } u_data;
+      u_data.real = this->data;
+      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        float real;
+        unsigned long base;
+      } u_data;
+      u_data.base = 0;
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->data = u_data.real;
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/Float32"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Float32MultiArray.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,75 @@
+#ifndef ros_Float32MultiArray_h
+#define ros_Float32MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class Float32MultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      unsigned char data_length;
+      float st_data;
+      float * data;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( unsigned char i = 0; i < data_length; i++){
+      union {
+        float real;
+        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 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 const char * getType(){ return "std_msgs/Float32MultiArray"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Float64.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,59 @@
+#ifndef ros_Float64_h
+#define ros_Float64_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace std_msgs
+{
+
+  class Float64 : public ros::Msg
+  {
+    public:
+      float data;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      long * val_data = (long *) &(this->data);
+      long exp_data = (((*val_data)>>23)&255);
+      if(exp_data != 0)
+        exp_data += 1023-127;
+      long sig_data = *val_data;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = (sig_data<<5) & 0xff;
+      *(outbuffer + offset++) = (sig_data>>3) & 0xff;
+      *(outbuffer + offset++) = (sig_data>>11) & 0xff;
+      *(outbuffer + offset++) = ((exp_data<<4) & 0xF0) | ((sig_data>>19)&0x0F);
+      *(outbuffer + offset++) = (exp_data>>4) & 0x7F;
+      if(this->data < 0) *(outbuffer + offset -1) |= 0x80;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      unsigned long * val_data = (unsigned long*) &(this->data);
+      offset += 3;
+      *val_data = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_data |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_data |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_data |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
+      unsigned long exp_data = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_data |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      if(exp_data !=0)
+        *val_data |= ((exp_data)-1023+127)<<23;
+      if( ((*(inbuffer+offset++)) & 0x80) > 0) this->data = -this->data;
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/Float64"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Float64MultiArray.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,79 @@
+#ifndef ros_Float64MultiArray_h
+#define ros_Float64MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class Float64MultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      unsigned char data_length;
+      float st_data;
+      float * data;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( unsigned char i = 0; i < data_length; i++){
+      long * val_datai = (long *) &(this->data[i]);
+      long exp_datai = (((*val_datai)>>23)&255);
+      if(exp_datai != 0)
+        exp_datai += 1023-127;
+      long sig_datai = *val_datai;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = (sig_datai<<5) & 0xff;
+      *(outbuffer + offset++) = (sig_datai>>3) & 0xff;
+      *(outbuffer + offset++) = (sig_datai>>11) & 0xff;
+      *(outbuffer + offset++) = ((exp_datai<<4) & 0xF0) | ((sig_datai>>19)&0x0F);
+      *(outbuffer + offset++) = (exp_datai>>4) & 0x7F;
+      if(this->data[i] < 0) *(outbuffer + offset -1) |= 0x80;
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      unsigned char data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (float*)realloc(this->data, data_lengthT * sizeof(float));
+      offset += 3;
+      data_length = data_lengthT;
+      for( unsigned char i = 0; i < data_length; i++){
+      unsigned long * val_st_data = (unsigned long*) &(this->st_data);
+      offset += 3;
+      *val_st_data = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07);
+      *val_st_data |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3;
+      *val_st_data |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11;
+      *val_st_data |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19;
+      unsigned long exp_st_data = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4;
+      exp_st_data |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4;
+      if(exp_st_data !=0)
+        *val_st_data |= ((exp_st_data)-1023+127)<<23;
+      if( ((*(inbuffer+offset++)) & 0x80) > 0) this->st_data = -this->st_data;
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(float));
+      }
+     return offset;
+    }
+
+   virtual const char * getType(){ return "std_msgs/Float64MultiArray"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Header.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,113 @@
+#ifndef ros_Header_h
+#define ros_Header_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "ros/time.h"
+
+namespace std_msgs
+{
+
+  class Header : public ros::Msg
+  {
+    public:
+      unsigned long seq;
+      ros::Time stamp;
+      char * frame_id;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_seq;
+      u_seq.real = this->seq;
+      *(outbuffer + offset + 0) = (u_seq.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_seq.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_seq.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_seq.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->seq);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_sec;
+      u_sec.real = this->stamp.sec;
+      *(outbuffer + offset + 0) = (u_sec.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_sec.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_sec.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_sec.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->stamp.sec);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_nsec;
+      u_nsec.real = this->stamp.nsec;
+      *(outbuffer + offset + 0) = (u_nsec.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_nsec.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_nsec.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_nsec.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->stamp.nsec);
+      long * length_frame_id = (long *)(outbuffer + offset);
+      *length_frame_id = strlen( (const char*) this->frame_id);
+      offset += 4;
+      memcpy(outbuffer + offset, this->frame_id, *length_frame_id);
+      offset += *length_frame_id;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_seq;
+      u_seq.base = 0;
+      u_seq.base |= ((typeof(u_seq.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_seq.base |= ((typeof(u_seq.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_seq.base |= ((typeof(u_seq.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_seq.base |= ((typeof(u_seq.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->seq = u_seq.real;
+      offset += sizeof(this->seq);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_sec;
+      u_sec.base = 0;
+      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->stamp.sec = u_sec.real;
+      offset += sizeof(this->stamp.sec);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_nsec;
+      u_nsec.base = 0;
+      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->stamp.nsec = u_nsec.real;
+      offset += sizeof(this->stamp.nsec);
+      uint32_t length_frame_id = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_frame_id; ++k){
+          inbuffer[k-1]=inbuffer[k];
+           }
+      inbuffer[offset+length_frame_id-1]=0;
+      this->frame_id = (char *)(inbuffer + offset-1);
+      offset += length_frame_id;
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/Header"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Int16.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,51 @@
+#ifndef ros_Int16_h
+#define ros_Int16_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace std_msgs
+{
+
+  class Int16 : public ros::Msg
+  {
+    public:
+      short data;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      union {
+        short real;
+        unsigned short base;
+      } u_data;
+      u_data.real = this->data;
+      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        short real;
+        unsigned short base;
+      } u_data;
+      u_data.base = 0;
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->data = u_data.real;
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "std_msgs/Int16"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Int16MultiArray.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,71 @@
+#ifndef ros_Int16MultiArray_h
+#define ros_Int16MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class Int16MultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      unsigned char data_length;
+      short st_data;
+      short * 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 {
+        short real;
+        unsigned short base;
+      } u_datai;
+      u_datai.real = this->data[i];
+      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      unsigned char data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (int*)realloc(this->data, data_lengthT * sizeof(int));
+      offset += 3;
+      data_length = data_lengthT;
+      for( unsigned char i = 0; i < data_length; i++){
+      union {
+        short real;
+        unsigned short 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));
+      }
+     return offset;
+    }
+
+   virtual const char * getType(){ return "std_msgs/Int16MultiArray"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Int32.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,55 @@
+#ifndef ros_Int32_h
+#define ros_Int32_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace std_msgs
+{
+
+  class Int32 : public ros::Msg
+  {
+    public:
+      long data;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      union {
+        long real;
+        unsigned long base;
+      } u_data;
+      u_data.real = this->data;
+      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        long real;
+        unsigned long base;
+      } u_data;
+      u_data.base = 0;
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->data = u_data.real;
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "std_msgs/Int32"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Int32MultiArray.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,75 @@
+#ifndef ros_Int32MultiArray_h
+#define ros_Int32MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class Int32MultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      unsigned char data_length;
+      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++){
+      union {
+        long 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 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++){
+      union {
+        long 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(long));
+      }
+     return offset;
+    }
+
+   virtual const char * getType(){ return "std_msgs/Int32MultiArray"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Int64.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,48 @@
+#ifndef ros_Int64_h
+#define ros_Int64_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace std_msgs
+{
+
+  class Int64 : public ros::Msg
+  {
+    public:
+      long data;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = (data >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset++) = (data >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset++) = (data >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset++) = (data >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset++) = (data > 0) ? 0: 255;
+      *(outbuffer + offset++) = (data > 0) ? 0: 255;
+      *(outbuffer + offset++) = (data > 0) ? 0: 255;
+      *(outbuffer + offset++) = (data > 0) ? 0: 255;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      data = 0;
+      data += ((long)(*(inbuffer + offset++))) >> (8 * 0);
+      data += ((long)(*(inbuffer + offset++))) >> (8 * 1);
+      data += ((long)(*(inbuffer + offset++))) >> (8 * 2);
+      data += ((long)(*(inbuffer + offset++))) >> (8 * 3);
+      offset += 4;
+     return offset;
+    }
+
+   virtual const char * getType(){ return "std_msgs/Int64"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Int64MultiArray.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,68 @@
+#ifndef ros_Int64MultiArray_h
+#define ros_Int64MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class Int64MultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      unsigned char data_length;
+      long st_data;
+      long * data;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( unsigned char i = 0; i < data_length; i++){
+      *(outbuffer + offset++) = (data[i] >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset++) = (data[i] >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset++) = (data[i] >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset++) = (data[i] >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset++) = (data[i] > 0) ? 0: 255;
+      *(outbuffer + offset++) = (data[i] > 0) ? 0: 255;
+      *(outbuffer + offset++) = (data[i] > 0) ? 0: 255;
+      *(outbuffer + offset++) = (data[i] > 0) ? 0: 255;
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      unsigned char data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (long*)realloc(this->data, data_lengthT * sizeof(long));
+      offset += 3;
+      data_length = data_lengthT;
+      for( unsigned char i = 0; i < data_length; i++){
+      st_data = 0;
+      st_data += ((long)(*(inbuffer + offset++))) >> (8 * 0);
+      st_data += ((long)(*(inbuffer + offset++))) >> (8 * 1);
+      st_data += ((long)(*(inbuffer + offset++))) >> (8 * 2);
+      st_data += ((long)(*(inbuffer + offset++))) >> (8 * 3);
+      offset += 4;
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(long));
+      }
+     return offset;
+    }
+
+   virtual const char * getType(){ return "std_msgs/Int64MultiArray"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Int8.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,49 @@
+#ifndef ros_Int8_h
+#define ros_Int8_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace std_msgs
+{
+
+  class Int8 : public ros::Msg
+  {
+    public:
+      signed char data;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      union {
+        signed char real;
+        unsigned char base;
+      } u_data;
+      u_data.real = this->data;
+      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        signed char real;
+        unsigned char base;
+      } u_data;
+      u_data.base = 0;
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->data = u_data.real;
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "std_msgs/Int8"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Int8MultiArray.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,69 @@
+#ifndef ros_Int8MultiArray_h
+#define ros_Int8MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class Int8MultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      unsigned char data_length;
+      signed char st_data;
+      signed char * 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 {
+        signed char real;
+        unsigned char base;
+      } u_datai;
+      u_datai.real = this->data[i];
+      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      unsigned char data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (signed char*)realloc(this->data, data_lengthT * sizeof(signed char));
+      offset += 3;
+      data_length = data_lengthT;
+      for( unsigned char i = 0; i < data_length; i++){
+      union {
+        signed char real;
+        unsigned char base;
+      } u_st_data;
+      u_st_data.base = 0;
+      u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->st_data = u_st_data.real;
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(signed char));
+      }
+     return offset;
+    }
+
+   virtual const char * getType(){ return "std_msgs/Int8MultiArray"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/MultiArrayDimension.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,91 @@
+#ifndef ros_MultiArrayDimension_h
+#define ros_MultiArrayDimension_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace std_msgs
+{
+
+  class MultiArrayDimension : public ros::Msg
+  {
+    public:
+      char * label;
+      unsigned long size;
+      unsigned long stride;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      long * length_label = (long *)(outbuffer + offset);
+      *length_label = strlen( (const char*) this->label);
+      offset += 4;
+      memcpy(outbuffer + offset, this->label, *length_label);
+      offset += *length_label;
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_size;
+      u_size.real = this->size;
+      *(outbuffer + offset + 0) = (u_size.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_size.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_size.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_size.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->size);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_stride;
+      u_stride.real = this->stride;
+      *(outbuffer + offset + 0) = (u_stride.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_stride.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_stride.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_stride.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->stride);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_label = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_label; ++k){
+          inbuffer[k-1]=inbuffer[k];
+           }
+      inbuffer[offset+length_label-1]=0;
+      this->label = (char *)(inbuffer + offset-1);
+      offset += length_label;
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_size;
+      u_size.base = 0;
+      u_size.base |= ((typeof(u_size.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_size.base |= ((typeof(u_size.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_size.base |= ((typeof(u_size.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_size.base |= ((typeof(u_size.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->size = u_size.real;
+      offset += sizeof(this->size);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_stride;
+      u_stride.base = 0;
+      u_stride.base |= ((typeof(u_stride.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_stride.base |= ((typeof(u_stride.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_stride.base |= ((typeof(u_stride.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_stride.base |= ((typeof(u_stride.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->stride = u_stride.real;
+      offset += sizeof(this->stride);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "std_msgs/MultiArrayDimension"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/MultiArrayLayout.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,75 @@
+#ifndef ros_MultiArrayLayout_h
+#define ros_MultiArrayLayout_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/MultiArrayDimension.h"
+
+namespace std_msgs
+{
+
+  class MultiArrayLayout : public ros::Msg
+  {
+    public:
+      unsigned char dim_length;
+      std_msgs::MultiArrayDimension st_dim;
+      std_msgs::MultiArrayDimension * dim;
+      unsigned long data_offset;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = dim_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( unsigned char i = 0; i < dim_length; i++){
+      offset += this->dim[i].serialize(outbuffer + offset);
+      }
+      union {
+        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 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 const char * getType(){ return "std_msgs/MultiArrayLayout"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/String.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,49 @@
+#ifndef ros_String_h
+#define ros_String_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include"mbed.h"
+
+
+namespace std_msgs
+{
+
+  class String : public ros::Msg
+  {
+    public:
+      char * data;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      long * length_data = (long *)(outbuffer + offset);
+      *length_data = strlen( (const char*) this->data);
+      offset += 4;
+      memcpy(outbuffer + offset, this->data, *length_data);
+      offset += *length_data;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_data = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_data; ++k){
+          inbuffer[k-1]=inbuffer[k];
+           }
+      inbuffer[offset+length_data-1]=0;
+      this->data = (char *)(inbuffer + offset-1);
+      offset += length_data;
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/String"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/Time.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,77 @@
+#ifndef ros_Time_h
+#define ros_Time_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "ros/time.h"
+
+namespace std_msgs
+{
+
+  class Time : public ros::Msg
+  {
+    public:
+      ros::Time data;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_sec;
+      u_sec.real = this->data.sec;
+      *(outbuffer + offset + 0) = (u_sec.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_sec.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_sec.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_sec.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data.sec);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_nsec;
+      u_nsec.real = this->data.nsec;
+      *(outbuffer + offset + 0) = (u_nsec.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_nsec.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_nsec.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_nsec.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data.nsec);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_sec;
+      u_sec.base = 0;
+      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->data.sec = u_sec.real;
+      offset += sizeof(this->data.sec);
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_nsec;
+      u_nsec.base = 0;
+      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->data.nsec = u_nsec.real;
+      offset += sizeof(this->data.nsec);
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/Time"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/UInt16.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,51 @@
+#ifndef ros_UInt16_h
+#define ros_UInt16_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace std_msgs
+{
+
+  class UInt16 : public ros::Msg
+  {
+    public:
+      unsigned short data;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      union {
+        unsigned short real;
+        unsigned short base;
+      } u_data;
+      u_data.real = this->data;
+      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        unsigned short real;
+        unsigned short base;
+      } u_data;
+      u_data.base = 0;
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      this->data = u_data.real;
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+    virtual const char * getType(){ return "std_msgs/UInt16"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/UInt16MultiArray.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,71 @@
+#ifndef ros_UInt16MultiArray_h
+#define ros_UInt16MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class UInt16MultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      unsigned char data_length;
+      unsigned short st_data;
+      unsigned short * 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 {
+        unsigned short real;
+        unsigned short base;
+      } u_datai;
+      u_datai.real = this->data[i];
+      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      unsigned char data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (unsigned int*)realloc(this->data, data_lengthT * sizeof(unsigned int));
+      offset += 3;
+      data_length = data_lengthT;
+      for( unsigned char i = 0; i < data_length; i++){
+      union {
+        unsigned short real;
+        unsigned short 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));
+      }
+     return offset;
+    }
+
+   virtual const char * getType(){ return "std_msgs/UInt16MultiArray"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/UInt32.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,55 @@
+#ifndef ros_UInt32_h
+#define ros_UInt32_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace std_msgs
+{
+
+  class UInt32 : public ros::Msg
+  {
+    public:
+      unsigned long data;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_data;
+      u_data.real = this->data;
+      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset + 2) = (u_data.base >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset + 3) = (u_data.base >> (8 * 3)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        unsigned long real;
+        unsigned long base;
+      } u_data;
+      u_data.base = 0;
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 1))) << (8 * 1);
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 2))) << (8 * 2);
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 3))) << (8 * 3);
+      this->data = u_data.real;
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "std_msgs/UInt32"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/UInt32MultiArray.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,75 @@
+#ifndef ros_UInt32MultiArray_h
+#define ros_UInt32MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class UInt32MultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      unsigned char data_length;
+      unsigned long st_data;
+      unsigned 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++){
+      union {
+        unsigned long 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 deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      unsigned char data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (unsigned long*)realloc(this->data, data_lengthT * sizeof(unsigned long));
+      offset += 3;
+      data_length = data_lengthT;
+      for( unsigned char i = 0; i < data_length; i++){
+      union {
+        unsigned long 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(unsigned long));
+      }
+     return offset;
+    }
+
+   virtual const char * getType(){ return "std_msgs/UInt32MultiArray"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/UInt64.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,48 @@
+#ifndef ros_UInt64_h
+#define ros_UInt64_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace std_msgs
+{
+
+  class UInt64 : public ros::Msg
+  {
+    public:
+      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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/UInt64MultiArray.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,68 @@
+#ifndef ros_UInt64MultiArray_h
+#define ros_UInt64MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class UInt64MultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      unsigned char data_length;
+      long st_data;
+      long * data;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.serialize(outbuffer + offset);
+      *(outbuffer + offset++) = data_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( unsigned char i = 0; i < data_length; i++){
+      *(outbuffer + offset++) = (data[i] >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset++) = (data[i] >> (8 * 1)) & 0xFF;
+      *(outbuffer + offset++) = (data[i] >> (8 * 2)) & 0xFF;
+      *(outbuffer + offset++) = (data[i] >> (8 * 3)) & 0xFF;
+      *(outbuffer + offset++) = (data[i] > 0) ? 0: 255;
+      *(outbuffer + offset++) = (data[i] > 0) ? 0: 255;
+      *(outbuffer + offset++) = (data[i] > 0) ? 0: 255;
+      *(outbuffer + offset++) = (data[i] > 0) ? 0: 255;
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      unsigned char data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (long*)realloc(this->data, data_lengthT * sizeof(long));
+      offset += 3;
+      data_length = data_lengthT;
+      for( unsigned char i = 0; i < data_length; i++){
+      st_data = 0;
+      st_data += ((long)(*(inbuffer + offset++))) >> (8 * 0);
+      st_data += ((long)(*(inbuffer + offset++))) >> (8 * 1);
+      st_data += ((long)(*(inbuffer + offset++))) >> (8 * 2);
+      st_data += ((long)(*(inbuffer + offset++))) >> (8 * 3);
+      offset += 4;
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(long));
+      }
+     return offset;
+    }
+
+   virtual const char * getType(){ return "std_msgs/UInt64MultiArray"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/UInt8.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,49 @@
+#ifndef ros_UInt8_h
+#define ros_UInt8_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace std_msgs
+{
+
+  class UInt8 : public ros::Msg
+  {
+    public:
+      unsigned char data;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      union {
+        unsigned char real;
+        unsigned char base;
+      } u_data;
+      u_data.real = this->data;
+      *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      union {
+        unsigned char real;
+        unsigned char base;
+      } u_data;
+      u_data.base = 0;
+      u_data.base |= ((typeof(u_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->data = u_data.real;
+      offset += sizeof(this->data);
+     return offset;
+    }
+
+   virtual const char * getType(){ return "std_msgs/UInt8"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/std_msgs/UInt8MultiArray.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,69 @@
+#ifndef ros_UInt8MultiArray_h
+#define ros_UInt8MultiArray_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "std_msgs/MultiArrayLayout.h"
+
+namespace std_msgs
+{
+
+  class UInt8MultiArray : public ros::Msg
+  {
+    public:
+      std_msgs::MultiArrayLayout layout;
+      unsigned char data_length;
+      unsigned char st_data;
+      unsigned char * 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 {
+        unsigned char real;
+        unsigned char base;
+      } u_datai;
+      u_datai.real = this->data[i];
+      *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
+      offset += sizeof(this->data[i]);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      offset += this->layout.deserialize(inbuffer + offset);
+      unsigned char data_lengthT = *(inbuffer + offset++);
+      if(data_lengthT > data_length)
+        this->data = (unsigned char*)realloc(this->data, data_lengthT * sizeof(unsigned char));
+      offset += 3;
+      data_length = data_lengthT;
+      for( unsigned char i = 0; i < data_length; i++){
+      union {
+        unsigned char real;
+        unsigned char base;
+      } u_st_data;
+      u_st_data.base = 0;
+      u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->st_data = u_st_data.real;
+      offset += sizeof(this->st_data);
+        memcpy( &(this->data[i]), &(this->st_data), sizeof(unsigned char));
+      }
+     return offset;
+    }
+
+   virtual const char * getType(){ return "std_msgs/UInt8MultiArray"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf/FrameGraph.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,68 @@
+#ifndef ros_SERVICE_FrameGraph_h
+#define ros_SERVICE_FrameGraph_h
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+
+namespace tf
+{
+
+static const char FRAMEGRAPH[] = "tf/FrameGraph";
+
+  class FrameGraphRequest : public ros::Msg
+  {
+    public:
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+     return offset;
+    }
+
+    const char * getType(){ return FRAMEGRAPH; };
+
+  };
+
+  class FrameGraphResponse : public ros::Msg
+  {
+    public:
+      char * dot_graph;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      long * length_dot_graph = (long *)(outbuffer + offset);
+      *length_dot_graph = strlen( (const char*) this->dot_graph);
+      offset += 4;
+      memcpy(outbuffer + offset, this->dot_graph, *length_dot_graph);
+      offset += *length_dot_graph;
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      uint32_t length_dot_graph = *(uint32_t *)(inbuffer + offset);
+      offset += 4;
+      for(unsigned int k= offset; k< offset+length_dot_graph; ++k){
+          inbuffer[k-1]=inbuffer[k];
+           }
+      inbuffer[offset+length_dot_graph-1]=0;
+      this->dot_graph = (char *)(inbuffer + offset-1);
+      offset += length_dot_graph;
+     return offset;
+    }
+
+    const char * getType(){ return FRAMEGRAPH; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf/tfMessage.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,53 @@
+#ifndef ros_tfMessage_h
+#define ros_tfMessage_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "../ros/msg.h"
+#include "geometry_msgs/TransformStamped.h"
+
+namespace tf
+{
+
+  class tfMessage : public ros::Msg
+  {
+    public:
+      unsigned char transforms_length;
+      geometry_msgs::TransformStamped st_transforms;
+      geometry_msgs::TransformStamped * transforms;
+
+    virtual int serialize(unsigned char *outbuffer)
+    {
+      int offset = 0;
+      *(outbuffer + offset++) = transforms_length;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      *(outbuffer + offset++) = 0;
+      for( unsigned char i = 0; i < transforms_length; i++){
+      offset += this->transforms[i].serialize(outbuffer + offset);
+      }
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      unsigned char transforms_lengthT = *(inbuffer + offset++);
+      if(transforms_lengthT > transforms_length)
+        this->transforms = (geometry_msgs::TransformStamped*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::TransformStamped));
+      offset += 3;
+      transforms_length = transforms_lengthT;
+      for( unsigned char i = 0; i < transforms_length; i++){
+      offset += this->st_transforms.deserialize(inbuffer + offset);
+        memcpy( &(this->transforms[i]), &(this->st_transforms), sizeof(geometry_msgs::TransformStamped));
+      }
+     return offset;
+    }
+
+    virtual const char * getType(){ return "tf/tfMessage"; };
+
+  };
+
+}
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/tf/transform_broadcaster.h	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,70 @@
+/* 
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2011, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ *  * Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *  * Redistributions in binary form must reproduce the above
+ *    copyright notice, this list of conditions and the following
+ *    disclaimer in the documentation and/or other materials provided
+ *    with the distribution.
+ *  * Neither the name of Willow Garage, Inc. nor the names of its
+ *    contributors may be used to endorse or promote prducts derived
+ *    from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+/* 
+ * Author: Michael Ferguson
+ */
+
+#ifndef ros_tf_h
+#define ros_tf_h
+
+#include "tfMessage.h"
+
+namespace tf
+{
+
+  class TransformBroadcaster
+  {
+    public:
+      TransformBroadcaster() : publisher_("tf", &internal_msg)
+      {
+        nh.advertise(publisher_);
+      }
+
+      void sendTransform(geometry_msgs::TransformStamped &transform)
+      {
+        internal_msg.transforms_length = 1;
+        internal_msg.transforms = &transform;
+        publisher_.publish(&internal_msg);
+      }
+
+    private:
+      tf::tfMessage internal_msg;
+      ros::Publisher publisher_;
+  };
+
+}
+
+#endif
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/time.cpp	Fri Aug 19 09:06:30 2011 +0000
@@ -0,0 +1,76 @@
+/* 
+ * 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
+ */
+
+#include "ros/time.h"
+#include "ros.h"
+
+
+namespace ros
+{
+  void normalizeSecNSec(unsigned long& sec, unsigned long& nsec){
+    unsigned long nsec_part= nsec % 1000000000UL;
+    unsigned long sec_part = nsec / 1000000000UL;
+    sec += sec_part;
+    nsec = nsec_part;
+  }
+
+  Time& Time::fromNSec(long t)
+  {
+    sec = t / 1000000000;
+    nsec = t % 1000000000;
+    normalizeSecNSec(sec, nsec);
+    return *this;
+  }
+
+  Time& Time::operator +=(const Duration &rhs)
+  {
+    sec += rhs.sec;
+    nsec += rhs.nsec;
+    normalizeSecNSec(sec, nsec);
+    return *this; 
+  }
+
+  Time& Time::operator -=(const Duration &rhs){
+    sec += -rhs.sec;
+    nsec += -rhs.nsec;
+    normalizeSecNSec(sec, nsec);
+    return *this;
+  }
+
+
+}