[Documentation] [TitleIndex] [WordIndex

rosserial overview: NodeHandles and Initialization | Messages | Publishers and Subscribers | Time | Logging | Limitations | Protocol | Parameters

Node Handles

rosserial_arduino allows you to easily connect an Arduino or other serial device to the ROS runtime graph. All of node initialization and communication is handled through a NodeHandle.

Creation of a NodeHandle is quite easy, before your setup() function:

ros::NodeHandle nh;

Initialization

One of the first calls you will likely execute in a your Arduino setup() function is the call to initNode(), which initializes the ROS node for the process. You can only have one node in a rosserial device, so you can only call initNode() once.

The following example shows a complete example of how to initialize a node and process the serial data inside the loop() function:

   1 #include <ros.h>
   2 
   3 ros::NodeHandle nh;
   4 
   5 void setup()
   6 {
   7   nh.initNode();
   8 }
   9 
  10 void loop()
  11 {
  12   nh.spinOnce();
  13 }

Custom Hardware Objects

The rosserial_client library does not actually provide a NodeHandle object directly. Instead it provides:

ros::NodeHandle_<HardwareType, MAX_PUBLISHERS=25, MAX_SUBSCRIBERS=25, IN_BUFFER_SIZE=512, OUT_BUFFER_SIZE=512> nh;

All client libraries are expected to provide a Hardware object and implement the default node handle type, typically in a ros.h file. For more information on customizing the hardware object, see Adding Support for New Hardware


2023-10-28 13:00