ros_serial for mbed updated to work with ROS Hydro. Library still needs to be debugged

Dependencies:   rosserial_hydro

Library and program still under development!

Revision:
0:cb1dffdc7d05
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/examples/Blink.cpp	Sun Feb 15 10:54:04 2015 +0000
@@ -0,0 +1,31 @@
+//#define COMPILE_BLINK_CODE_ROSSERIAL
+#ifdef COMPILE_BLINK_CODE_ROSSERIAL
+
+/*
+ * rosserial Subscriber Example
+ * Blinks an LED on callback
+ */
+#include "mbed.h"
+#include <ros.h>
+#include <std_msgs/Empty.h>
+
+ros::NodeHandle  nh;
+DigitalOut myled(LED1);
+
+void messageCb( const std_msgs::Empty& toggle_msg) {
+    myled = !myled;   // blink the led
+}
+
+ros::Subscriber<std_msgs::Empty> sub("toggle_led", &messageCb );
+
+int main() {
+    nh.initNode();
+    nh.subscribe(sub);
+
+    while (1) {
+        nh.spinOnce();
+        wait_ms(1);
+    }
+}
+
+#endif
\ No newline at end of file