rosserial mbed for Float64MultiArray (In this program, the topic name is "chatter"). you need the node at PC who send Float64MultiArray (In this program, the topic name is "req". And the number of data is same as the returning data ("chatter", in this program, 5 data)). The example is written at comment.

Dependencies:   mbed ros_lib_indigo

Fork of rosserial_mbed_hello_world_publisher by Gary Servin

Revision:
2:b740e3e4c6c9
Parent:
1:c7411b1ccd0f
--- a/main.cpp	Tue Oct 25 06:29:41 2016 +0000
+++ b/main.cpp	Tue Oct 25 07:12:07 2016 +0000
@@ -2,74 +2,29 @@
  * rosserial Publisher Example
  * Prints "hello world!"
  */
-/*
-#include"mbed.h"
-#include <ros.h>
-#include <std_msgs/String.h>
 
-ros::NodeHandle  nh;
+/* ROS node program
+#include <ros/ros.h>
+#include <std_msgs/Float64MultiArray.h>
 
-std_msgs::String str_msg;
-ros::Publisher chatter("chatter", &str_msg);
-
-char hello[13] = "hello world0";
-
-DigitalOut led = LED1;
+int main(int argc,char **argv){
+  ros::init(argc,argv,"serial_test");
+  ros::NodeHandle n;
+  ros::Publisher req_pub=n.advertise<std_msgs::Float64MultiArray>("req", 1000);
 
-int main() {
-    int num=0;
-    nh.getHardware()->setBaud(115200);
-    nh.initNode();
-    nh.advertise(chatter);
-
-    while (1) {
-        led = !led;
-        hello[11]=num+48;
-        str_msg.data = hello;
-        chatter.publish( &str_msg );
-        nh.spinOnce();
-        wait_ms(2);
-        num++;
-        if(num>9)num=0;
-    }
+  ros::Rate loop_rate(174);
+  while (ros::ok()){
+    std_msgs::Float64MultiArray msg;
+    msg.data.clear();
+    for(int i=0;i<5;i++)msg.data.push_back(0);
+    req_pub.publish(msg);
+    ROS_INFO("send");
+    ros::spinOnce();
+    loop_rate.sleep();
+  }
+  return 0;
 }
 */
-/*
-#include"mbed.h"
-#include <ros.h>
-#include <std_msgs/Float64MultiArray.h>
-
-ros::NodeHandle  nh;
-
-std_msgs::Float64MultiArray str_msg;
-
-double data[5]={0.1,0.2,0.3,0.4,0};
-
-DigitalOut led = LED1;
-
-int main() {
-    nh.getHardware()->setBaud(115200);
-    nh.initNode();
-    str_msg.layout.dim_length=1;
-    str_msg.data_length=5;
-    str_msg.layout.dim = (std_msgs::MultiArrayDimension *)
-    malloc(sizeof(std_msgs::MultiArrayDimension) * 2);
-    str_msg.layout.dim[0].label = "chatter";
-    str_msg.layout.dim[0].size = 5;
-    str_msg.layout.dim[0].stride = 1*5;
-    str_msg.layout.data_offset = 0;
-    str_msg.data = (double *)malloc(sizeof(double)*5);
-    ros::Publisher chatter("chatter", &str_msg);
-    nh.advertise(chatter);
-    while (1) {
-        led = !led;
-        data[4]+=0.1;
-        for(int i=0;i<5;i++)str_msg.data[i] = data[i];
-        chatter.publish( &str_msg );
-        nh.spinOnce();
-        wait_ms(1000);
-    }
-}*/
 
 #include <ros.h>
 #include "mbed.h"