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

Revision:
0:77afd7560544
Child:
1:ff0ec969dad1
--- /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