## For instruction on writing tutorials ## http://www.ros.org/wiki/WritingTutorials #################################### ##FILL ME IN #################################### ## for a custom note with links: ## note = ## for the canned note of "This tutorial assumes that you have completed the previous tutorials:" just add the links ## note.0= [[rosserial_arduino/Tutorials/Hello World|Hello World (example Publisher)]] ## descriptive title for the tutorial ## title = Blink (example subscriber) ## multi-line description to be displayed in search ## description = This tutorial shows step by step how to use rosserial with subscribers. ## the next tutorial description (optional) ## next = ## links to next tutorial (optional) ## next.0.link=[[rosserial_arduino/Tutorials/Logging|Logging]] ## next.1.link= ## what level user is this tutorial for ## level= BeginnerCategory ## keywords = #################################### <> <> <> == Blink: Creating a Subscriber == === The Code === Now that we've created a ROS publisher in the [[rosserial_arduino/Tutorials/Hello World|previous tutorial]], we'll create a subscriber. If you have followed the [[rosserial_arduino/Tutorials/Arduino IDE Setup|Arduino IDE Setup tutorial]], you'll be able to open the sketch below by choosing `ros_lib -> Blink` from the Arduino examples menu. This should open the following code in your IDE: {{{#!cplusplus block=blink /* * rosserial Subscriber Example * Blinks an LED on callback */ #include #include ros::NodeHandle nh; void messageCb( const std_msgs::Empty& toggle_msg){ digitalWrite(13, HIGH-digitalRead(13)); // blink the led } ros::Subscriber sub("toggle_led", &messageCb ); void setup() { pinMode(13, OUTPUT); nh.initNode(); nh.subscribe(sub); } void loop() { nh.spinOnce(); delay(1); } }}} === The Code Explained === Now, let's break the code down. {{{ #include #include }}} As before, we need to include the `ros.h` as with any other ROS Arduino program. We also include the header files for messages, in this case, the `Empty` message. {{{ ros::NodeHandle nh; }}} Next, we need to instantiate the node handle, which allows our program to create publishers and subscribers. The node handle also takes care of serial port communications. {{{ void messageCb( const std_msgs::Empty& toggle_msg){ digitalWrite(13, HIGH-digitalRead(13)); // blink the led } }}} We then create the callback function for our subscriber. The call back function must take a constant reference of a message as its argument. In our callback `messageCb`, the type of message is `std_msgs::Empty` and the message name will be `toggle_msg`. Inside our callback, we could reference `toggle_msg`, but since it is empty, there is no need to. We just blink the LED on the Arduino every time we receive a message. {{{ ros::Subscriber sub("toggle_led", &messageCb ); }}} We need to instantiate the publishers and subscribers that we will be using. Here we instantiate a Subscriber with a topic name of "toggle_led" and type `std_msgs::Empty`. With Subscribers, you must remember to template the subscriber upon the message. Its two arguments are the topic it will be subscribing to and the callback function it will be using. {{{ void setup() { pinMode(13, OUTPUT); nh.initNode(); nh.subscribe(sub); } }}} In the Arduino setup function you then need to initialize your ROS node handle, advertise any topics being published, and subscribe to any topics you wish to listen to. {{{ void loop() { nh.spinOnce(); delay(1); } }}} Finally, in the loop function we call ros::spinOnce() where all of the ROS communication callbacks are handled. We don't need to do any additional processing in the `loop()`, since ros::spinOnce() will handle passing messages to the subscriber callback. === Uploading the Code === To upload the code to your Arduino, use the upload function within the Arduino IDE. This is no different from uploading any other sketch. === Running the Code === Now, launch the [[roscore]] in a new terminal window: {{{ roscore }}} Next, run the rosserial client application that forwards your Arduino messages to the rest of ROS. Make sure to use the correct serial port: {{{ rosrun rosserial_python serial_node.py /dev/ttyUSB0 }}} Finally, you can toggle the LED using [[rostopic]]: {{{ rostopic pub toggle_led std_msgs/Empty --once }}} == Further Reading == Please see [[rosserial/Overview/Publishers and Subscribers|rosserial/Overview]] for more information on publishers and subscribers. Also see [[rosserial/Overview/Limitations|limitations]] for information about more complex data types. To generate header files for your custom messages, check [[http://wiki.ros.org/rosserial_arduino/Tutorials/Adding%20Custom%20Messages|rosserial_arduino/Tutorials/Adding Custom Messages]] tutorial. ## AUTOGENERATED DO NOT DELETE ## TutorialCategory ## FILL IN THE STACK TUTORIAL CATEGORY HERE