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

tests/float64_test.cpp

Committer:
nucho
Date:
2011-08-19
Revision:
0:06fc856e99ca
Child:
1:098e75fd5ad2

File content as of revision 0:06fc856e99ca:

//#define COMPLIE_FLOAT64_CODE_ROSSERIAL
#ifdef COMPILE_FLOAT64_CODE_ROSSERIAL

/*
 * rosserial::std_msgs::Float64 Test
 * Receives a Float64 input, subtracts 1.0, and publishes it
 */

#include "mbed.h"
#include <ros.h>
#include <std_msgs/Float64.h>


ros::NodeHandle nh;

float x;
DigitalOut myled(LED1);

void messageCb( const std_msgs::Float64& msg) {
    x = msg.data - 1.0;
    myled = !myled; // blink the led
}

std_msgs::Float64 test;
ros::Subscriber<std_msgs::Float64> s("your_topic", &messageCb);
ros::Publisher p("my_topic", &test);

int main() {
    nh.initNode();
    nh.advertise(p);
    nh.subscribe(s);
    while (1) {
        test.data = x;
        p.publish( &test );
        nh.spinOnce();
        wait_ms(10);
    }
}
#endif