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

Dependencies:   rosserial_mbed_lib mbed Servo

Revision:
3:dff241b66f84
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/rosserial_arduino/Adc.h	Sat Nov 12 23:53:04 2011 +0000
@@ -0,0 +1,76 @@
+#ifndef _ROS_rosserial_arduino_Adc_h
+#define _ROS_rosserial_arduino_Adc_h
+
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include "ros/msg.h"
+
+namespace rosserial_arduino
+{
+
+  class Adc : public ros::Msg
+  {
+    public:
+      uint16_t adc0;
+      uint16_t adc1;
+      uint16_t adc2;
+      uint16_t adc3;
+      uint16_t adc4;
+      uint16_t adc5;
+
+    virtual int serialize(unsigned char *outbuffer) const
+    {
+      int offset = 0;
+      *(outbuffer + offset + 0) = (this->adc0 >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->adc0 >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->adc0);
+      *(outbuffer + offset + 0) = (this->adc1 >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->adc1 >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->adc1);
+      *(outbuffer + offset + 0) = (this->adc2 >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->adc2 >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->adc2);
+      *(outbuffer + offset + 0) = (this->adc3 >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->adc3 >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->adc3);
+      *(outbuffer + offset + 0) = (this->adc4 >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->adc4 >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->adc4);
+      *(outbuffer + offset + 0) = (this->adc5 >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 1) = (this->adc5 >> (8 * 1)) & 0xFF;
+      offset += sizeof(this->adc5);
+      return offset;
+    }
+
+    virtual int deserialize(unsigned char *inbuffer)
+    {
+      int offset = 0;
+      this->adc0 |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->adc0 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      offset += sizeof(this->adc0);
+      this->adc1 |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->adc1 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      offset += sizeof(this->adc1);
+      this->adc2 |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->adc2 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      offset += sizeof(this->adc2);
+      this->adc3 |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->adc3 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      offset += sizeof(this->adc3);
+      this->adc4 |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->adc4 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      offset += sizeof(this->adc4);
+      this->adc5 |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0);
+      this->adc5 |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
+      offset += sizeof(this->adc5);
+     return offset;
+    }
+
+    const char * getType(){ return "rosserial_mbed/Adc"; };
+    const char * getMD5(){ return "6d7853a614e2e821319068311f2af25b"; };
+
+  };
+
+}
+#endif
\ No newline at end of file