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:
3:1cf99502f396
Parent:
1:ff0ec969dad1
--- a/rosserial_msgs/Log.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/rosserial_msgs/Log.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,10 +1,10 @@
-#ifndef ros_rosserial_msgs_Log_h
-#define ros_rosserial_msgs_Log_h
+#ifndef _ROS_rosserial_msgs_Log_h
+#define _ROS_rosserial_msgs_Log_h
 
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 
 namespace rosserial_msgs
 {
@@ -12,7 +12,7 @@
   class Log : public ros::Msg
   {
     public:
-      unsigned char level;
+      uint8_t level;
       char * msg;
       enum { DEBUG = 0 };
       enum { INFO = 1 };
@@ -20,17 +20,12 @@
       enum { ERROR = 3 };
       enum { FATAL = 4 };
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
-      union {
-        unsigned char real;
-        unsigned char base;
-      } u_level;
-      u_level.real = this->level;
-      *(outbuffer + offset + 0) = (u_level.base >> (8 * 0)) & 0xFF;
+      *(outbuffer + offset + 0) = (this->level >> (8 * 0)) & 0xFF;
       offset += sizeof(this->level);
-      long * length_msg = (long *)(outbuffer + offset);
+      uint32_t * length_msg = (uint32_t *)(outbuffer + offset);
       *length_msg = strlen( (const char*) this->msg);
       offset += 4;
       memcpy(outbuffer + offset, this->msg, *length_msg);
@@ -41,19 +36,13 @@
     virtual int deserialize(unsigned char *inbuffer)
     {
       int offset = 0;
-      union {
-        unsigned char real;
-        unsigned char base;
-      } u_level;
-      u_level.base = 0;
-      u_level.base |= ((typeof(u_level.base)) (*(inbuffer + offset + 0))) << (8 * 0);
-      this->level = u_level.real;
+      this->level |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
       offset += sizeof(this->level);
       uint32_t length_msg = *(uint32_t *)(inbuffer + offset);
       offset += 4;
       for(unsigned int k= offset; k< offset+length_msg; ++k){
           inbuffer[k-1]=inbuffer[k];
-           }
+      }
       inbuffer[offset+length_msg-1]=0;
       this->msg = (char *)(inbuffer + offset-1);
       offset += length_msg;
@@ -61,6 +50,7 @@
     }
 
     virtual const char * getType(){ return "rosserial_msgs/Log"; };
+    virtual const char * getMD5(){ return "7170d5aec999754ba0d9f762bf49b913"; };
 
   };