pubsub.cpp
Go to the documentation of this file.
00001 /*
00002  * rosserial PubSub Example
00003  * Prints "hello world!" and toggles led
00004  */
00005 
00006 #include "rosADK.h"
00007 #include <std_msgs/String.h>
00008 #include <std_msgs/Empty.h>
00009 #include <util/delay.h>
00010 
00011 //ros::NodeHandle_<ArduinoHardware,1,1,100,100>  nh;
00012 
00013 ros::NodeHandle  nh;
00014 
00015 std_msgs::String str_msg;
00016 ros::Publisher chatter("chatter", &str_msg);
00017 
00018 char rsp_str[]="responding to toggle";
00019 
00020 void messageCb( const std_msgs::Empty& toggle_msg){
00021   digitalWrite(13, HIGH-digitalRead(13));   // blink the led
00022   
00023   //str_msg.data = rsp_str;
00024   //chatter.publish( &str_msg );
00025 }
00026 
00027 ros::Subscriber<std_msgs::Empty> sub("toggle_led", messageCb );
00028 
00029 
00030 
00031 char hello[13] = "hello world!";
00032 
00033 void setup()
00034 {
00035   pinMode(13, OUTPUT);
00036   nh.initNode();
00037   nh.advertise(chatter);
00038   nh.subscribe(sub);
00039 }
00040 
00041 void loop()
00042 {
00043   str_msg.data = hello;
00044   chatter.publish( &str_msg );
00045 
00046   nh.spinOnce();
00047   _delay_ms(500);
00048 }


rosserial_adk_demo
Author(s): Adam Stambler
autogenerated on Mon Dec 2 2013 12:02:02