## 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/Arduino IDE Setup|Arduino IDE Setup]] ## descriptive title for the tutorial ## title = Hello World (example publisher) ## multi-line description to be displayed in search ## description = This tutorial shows step by step how to create a publisher using rosserial. ## the next tutorial description (optional) ## next = ## links to next tutorial (optional) ## next.0.link= [[rosserial_arduino/Tutorials/Blink|Blink (example subscriber)]] ## next.1.link= ## what level user is this tutorial for ## level= BeginnerCategory ## keywords = #################################### <> <> <> == Hello World: Creating a Publisher == === The Code === We'll start our exploration into rosserial by creating a "hello world" program for our Arduino. (Note: the Arduino community often calls source code for programs a "sketch", we will use the same convention below). 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 -> HelloWorld` from the Arduino `examples` menu. This should open the following code in your IDE: {{{#!cplusplus block=helloworld /* * rosserial Publisher Example * Prints "hello world!" */ // Use the following line if you have a Leonardo or MKR1000 //#define USE_USBCON #include #include ros::NodeHandle nh; std_msgs::String str_msg; ros::Publisher chatter("chatter", &str_msg); char hello[13] = "hello world!"; void setup() { nh.initNode(); nh.advertise(chatter); } void loop() { str_msg.data = hello; chatter.publish( &str_msg ); nh.spinOnce(); delay(1000); } }}} === The Code Explained === Now, let's break the code down. {{{ // Use the following line if you have a Leonardo or MKR1000 }}} Use the following line if you have a Leonardo or MKR1000 or any other device that has a native USB port, which is different than on the Arduino UNO, MEGA. Otherwise you will receive an error similar to the following: {{{ [ERROR] [1524089506.982801]: Unable to sync with device; possible link problem or link software version mismatch such as hydro rosserial_python with groovy Arduino }}} {{{ #include #include }}} As a part of every ROS Arduino program, you need to include the `ros.h` header file and header files for any messages that you will be using. {{{ 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. {{{ std_msgs::String str_msg; ros::Publisher chatter("chatter", &str_msg); char hello[13] = "hello world!"; }}} We need to instantiate the publishers and subscribers that we will be using. Here we instantiate a Publisher with a topic name of "chatter". The second parameter to Publisher is a reference to the message instance to be used for publishing. {{{ void setup() { nh.initNode(); nh.advertise(chatter); } }}} 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() { str_msg.data = hello; chatter.publish( &str_msg ); nh.spinOnce(); delay(1000); } }}} Finally, in the loop function, the node publishes "Hello World" and calls `ros::spinOnce()` where all of the ROS communication callbacks are handled. === Compiling the Code === To compile the code, use the compile function within the Arduino IDE. This is no different from uploading any other sketch. Once the compilation is completed, you will receive a message about program storage space and dynamic memory usage, similar to this: {{{ Sketch uses 9,392 bytes (29%) of program storage space. Maximum is 32,256 bytes. Global variables use 1,356 bytes (66%) of dynamic memory, leaving 692 bytes for local variables. Maximum is 2,048 bytes. }}} The program storage space is less important, as long as you use less than the total storage available, your code will run fine. The dynamic memory usage is something you should be careful about, as local variables inside of an function, unallocated objects, interrupts, and stacks all can change how much free memory you have. If you run out of the memory, your microcontroller will simply freeze with no debug information. If you encounters random freezes or your Arduino unable to communicate with ROS while your code compiles fine, but dynamic memory usage is high, you might need to reduce the memory used by `rosserial`. Refer to [[http://wiki.ros.org/rosserial?#Limitations|rosserial Limitations]] and [[rosserial_arduino/Tutorials/NodeHandle and ArduinoHardware|NodeHandle and ArduinoHardware]] for more information. === 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 }}} {{{{#!wiki version hydro indigo {{{ rosrun rosserial_python serial_node.py _port:=/dev/ttyUSB0 }}} }}}} {{{{#!wiki version groovy {{{ rosrun rosserial_python serial_node.py /dev/ttyUSB0 }}} }}}} Alternatively, if you want the ability to programmatically reset your Arduino, run using: {{{ rosrun rosserial_arduino serial_node.py _port:=/dev/ttyUSB0 }}} This will automatically provide a service endpoint at `~reset_arduino` that you can call which will have the same effect as pressing the Arduino's reset button. Finally, watch the greetings come in from your Arduino by launching a new terminal window and entering: {{{ rostopic echo chatter }}} == 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