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
examples/pubsub.cpp@0:06fc856e99ca, 2011-08-19 (annotated)
- Committer:
- nucho
- Date:
- Fri Aug 19 09:06:16 2011 +0000
- Revision:
- 0:06fc856e99ca
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
nucho | 0:06fc856e99ca | 1 | //#define COMPILE_PUBSUB_CODE_ROSSERIAL |
nucho | 0:06fc856e99ca | 2 | #ifdef COMPILE_PUBSUB_CODE_ROSSERIAL |
nucho | 0:06fc856e99ca | 3 | |
nucho | 0:06fc856e99ca | 4 | /* |
nucho | 0:06fc856e99ca | 5 | * rosserial PubSub Example |
nucho | 0:06fc856e99ca | 6 | * Prints "hello world!" and toggles led |
nucho | 0:06fc856e99ca | 7 | */ |
nucho | 0:06fc856e99ca | 8 | #include "mbed.h" |
nucho | 0:06fc856e99ca | 9 | #include <ros.h> |
nucho | 0:06fc856e99ca | 10 | #include <std_msgs/String.h> |
nucho | 0:06fc856e99ca | 11 | #include <std_msgs/Empty.h> |
nucho | 0:06fc856e99ca | 12 | |
nucho | 0:06fc856e99ca | 13 | ros::NodeHandle nh; |
nucho | 0:06fc856e99ca | 14 | DigitalOut myled(LED1); |
nucho | 0:06fc856e99ca | 15 | |
nucho | 0:06fc856e99ca | 16 | void messageCb( const std_msgs::Empty& toggle_msg) { |
nucho | 0:06fc856e99ca | 17 | myled = !myled; // blink the led |
nucho | 0:06fc856e99ca | 18 | } |
nucho | 0:06fc856e99ca | 19 | |
nucho | 0:06fc856e99ca | 20 | ros::Subscriber<std_msgs::Empty> sub("toggle_led", messageCb ); |
nucho | 0:06fc856e99ca | 21 | |
nucho | 0:06fc856e99ca | 22 | |
nucho | 0:06fc856e99ca | 23 | |
nucho | 0:06fc856e99ca | 24 | std_msgs::String str_msg; |
nucho | 0:06fc856e99ca | 25 | ros::Publisher chatter("chatter", &str_msg); |
nucho | 0:06fc856e99ca | 26 | |
nucho | 0:06fc856e99ca | 27 | char hello[13] = "hello world!"; |
nucho | 0:06fc856e99ca | 28 | |
nucho | 0:06fc856e99ca | 29 | int main() { |
nucho | 0:06fc856e99ca | 30 | nh.initNode(); |
nucho | 0:06fc856e99ca | 31 | nh.advertise(chatter); |
nucho | 0:06fc856e99ca | 32 | nh.subscribe(sub); |
nucho | 0:06fc856e99ca | 33 | |
nucho | 0:06fc856e99ca | 34 | while (1) { |
nucho | 0:06fc856e99ca | 35 | str_msg.data = hello; |
nucho | 0:06fc856e99ca | 36 | chatter.publish( &str_msg ); |
nucho | 0:06fc856e99ca | 37 | nh.spinOnce(); |
nucho | 0:06fc856e99ca | 38 | wait_ms(500); |
nucho | 0:06fc856e99ca | 39 | } |
nucho | 0:06fc856e99ca | 40 | } |
nucho | 0:06fc856e99ca | 41 | #endif |