Contents
AVR _BRIDGE IS DEPRECIATED . DO NOT USE IN A NEW PROJECT. USE ROSSERIAL INSTEAD.
avr_bridge is meant to simplify the use of an Arduino and avr processors in a ROS based robot by providing a partial ROS implementation in avr c++. In hobbyist robotics, these microcontrollers are often used to read sensors and perform low level motor control. Every time a robot needs to interface with an AVR board, a new communication system is written. Typically they all use a usb-to-serial converter and either a custom binary or text based protocol. AVR bridge replaces these custom protocols with an automatically generated ROS communication stack that allows the AVR processors to directly publish or subscribe to ROS topics.
AVR bridge system consists of three different programs. An AVR c++ source generator, the resulting using avr program, and an avr_bridge python node which does the actual ROS publishing/subscribing. The source generator and the bridge node both use a configuration file to automatically generate the communication stack.
Configuration file
Every avr_bridge program needs a yaml configuration file which specifies the port name, the subscriptions, and the publications that each avr handles. This is an example configuration file:
port: /dev/ttyUSB0 name: callResponse publish: #list of published topics response: #topic name type: std_msgs/String #msg type subscribe: #list of subscripitions call: type: std_msgs/String
gen_avr.py : avr_ros source generator
The gen_avr.py script is an avr c++ msg generator. To run gen_avr, perform
rosrun avr_bridge gen_avr.py <config file> <avr src path>
This command will generate an avr_ros folder to be included in your avr project. This folder has the base msg objects and the avr C++
API
gen_avr.py will create a directory called avr_ros within the specified path. This directory contains several autogenerated C++ files whose purpose is to handle serialization and deserialization of messages.
In the avr_ros directory a file called "ros.h" exists which contains an instance of ros::NodeHandle (note that this is not the same as the ros::NodeHandle defined in the roscpp api) with the name node. All interaction with avr_ros is done via node.
The user must have defined a int ros::fputc(char c, FILE *f) function which may be used to send bytes to the controlling device. Most often, this means sending bytes out the USART (also: Serial) port on the micro-controller to a connected computer.
The following is an example of this for the Arduino environment.
To let the node processes the in coming communication, run
1 node.spin();
Subscriptions
For every subscription, a callback function and callback message must be registered using ros.subscribe:
thus, an example usage is
Note that the callback function may not be a member due to our lack of boost.
The message object is used for both deserialization and storage of the deserialized data.
Publishing Messages
Publisher ros::NodeHandler::advertise(char const *topic_name) returns a unique identifier for the given topic. Data may be sent to the controlling device by calling void ros::NodeHandler::publish(Publisher pub, Msg *msg).
Note that Publisher is presently a uint8_t.
See the callResponse tutorial for a complete example.
bridge_node.py
- bridge_node.py is the default method for using AVR processors as first class ROS components. The bridge node reads in the configuration file and automatically publishes data sent from your avr processor. It uses pyserial to talk to the avr processor. It expects to have the configuration yaml file as its first argument. It automatically opens the avr port starts talking to the avr, and subscribes and publishes the messages. To use run:
rosrun avr_bridge bridge_node.py <config file>
System Caveats
float64 UNSUPPORTED : An 8bit microcontroller is not a PC. It cannot handle 64bit floating point numbers and as a result, there is no compiler support for float64. In the current avr_bridge system, there is no support for ROS messages that use float64. It will correctly parse the other fields, but the float value will be garbage.
Every variable length message field need to be initialized with a maximum length. This includes any arrays and strings. To do so, use msg.setMaxLength( length ). This is needed because avr microcontrollers have a very small RAM which cannot handle heavy dynamic allocation. Therefore, it is up to the program designer to specify this max length . All data past this max length is ignored.
For a more in depth explanation of c++ programming with embedded processor constraints, see http://nrqm.ca/mechatronics-lab-guide/lab-guide-embedded-memory-management/