Only released in EOL distros:  

ros_arduino_bridge: ros_arduino_firmware | ros_arduino_msgs | ros_arduino_python

Package Summary

ROS Arduino Python

ros_arduino_bridge: ros_arduino_firmware | ros_arduino_msgs | ros_arduino_python

Package Summary

ROS Arduino Python

ros_arduino_bridge: ros_arduino_firmware | ros_arduino_msgs | ros_arduino_python

Package Summary

ROS Arduino Python.

ros_arduino_bridge: ros_arduino_firmware | ros_arduino_msgs | ros_arduino_python

Package Summary

ROS Arduino Python.

Overview

This package consists of a Python driver and ROS node for Arduino-compatible controllers. The Arduino must be connected to a PC or SBC using either a USB port or an RF serial link (e.g. XBee).

Features

  • Direct support for the following sensors:
    • Ping sonar
    • Sharp infrared (GP2D12)
    • Onboard Pololu motor controller current
    • Phidgets Voltage sensor
    • Phidgets Current sensor (DC, 20A)
  • Can also read data from generic analog and digital sensors
  • Can control digital outputs (e.g. turn a switch or LED on and off)
  • Support for PWM servos
  • Configurable base controller if using the required hardware.

Arduino Node

arduino-node.py

A ROS node for Arduino-compatible microcontrollers. Sensors can be polled at independent rates (see sample config file at the end of this page.) For example, main voltage could be polled at 1 Hz while a sonar sensor could be polled at 20 Hz.

Subscribed Topics

/cmd_vel (geometry_msgs/Twist)
  • Movement commands for the base controller.

Published Topics

/odom (nav_msgs/Odometry)
  • Odometry messages from the base controller.
~sensor_state (ros_arduino_msgs/SensorState)
  • An array of sensor names and values.
~sensor/name (sensor_msgs/Range,)
  • Each sensor value is published on its own topic under the "sensor" namespace with the appropriate type. See sample config file below for examples.

Services

~servo_write (ros_arduino_msgs/ServoWrite)
  • Set the target position of a servo with index 'id' to 'value' (in radians). The 'id' to pin mapping is made in the Arduino firmware.
~servo_read (ros_arduino_msgs/ServoRead)
  • Get the last set position (in radians) from the servo with index 'id'.
~digital_set_direction (ros_arduino_msgs/DigitalSetDirection)
  • Sets a digital pin to INPUT (0) or OUTPUT (1)
~digital_write (ros_arduino_msgs/DigitalWrite)
  • Sets a digital pin either LOW (0) or HIGH (1)

Parameters

~port (str, default: /dev/ttyUSB0 -- some controllers use /dev/ttyACM0)
  • Serial port.
~baud (int, default: 57600)
  • Baud rate for the serial connection.
~timeout (float, default: 0.1)
  • Timeout for serial port in seconds.
~rate (int, default: 50)
  • Rate to run the main control loop. Should be at least as fast as the faster sensor rate.
~sensorstate_rate (int, default: 10)
  • Rate to publish the overall sensor array. Note that individual sensors are published on their own topics and at their own rate.
~use_base_controller (bool, default: False)
  • Whether or not to use the base controller.
~base_controller_rate (int, default: 10)
  • Rate to publish odometry data.
~base_frame (New in Hydro) (string, default: base_link)
  • Link to use as the base link when publishing odometry
~wheel_diameter (float, default: none)
  • Wheel diameter in meters.
~wheel_track (float, default: none)
  • Wheel track in meters. (Distance between centers of drive wheels.)
~encoder_resolution (int, default: none)
  • Encoder ticks per wheel revolution.
~gear_reduction (float, default: 1.0)
  • External gear reduction.
~motors_reversed (bool, default: False)
  • Reverse the sense of wheel rotation.
~Kp (int, default: 20)
  • Proportial PID parameter.
~Kd (int, default: 12)
  • Derivative PID parameter.
~Ki (int, default: 0)
  • Integral PID parameter.
~Ko (int, default: 50)
  • Output PID parameter.
~accel_limit (float, default: 0.1)
  • Max acceleration when changing wheel speeds
~sensors (dict, default: None)
  • Dictionary of sensors attached to the Arduino. (See the sample YAML config file below.)

Provided tf Transforms

odombase_link
  • Transform needed for navigation.

Configuration

The Arduino node is configured using a YAML file specifying the required parameters. A sample parameter file called arduino_params.yaml is included in the config directory and is shown below. Make a copy of this file(e.g. my_arduino_params.yaml) before editing. Note that many of the parameters are commented out and must be set and un-commented before you can use the node with your Arduino.

Current valid sensor types names (case-sensitive):

port: /dev/ttyUSB0
baud: 57600
timeout: 0.1

rate: 50
sensorstate_rate: 10

use_base_controller: False
base_controller_rate: 10

# === Robot drivetrain parameters
#wheel_diameter: 0.146
#wheel_track: 0.2969
#encoder_resolution: 8384 # from Pololu for 131:1 motors
#gear_reduction: 1.0
#motors_reversed: True

# === PID parameters
#Kp: 20
#Kd: 12
#Ki: 0
#Ko: 50
#accel_limit: 1.0

# === Sensor definitions.  Examples only - edit for your robot.
#     Sensor type can be one of the follow (case sensitive!):
#         * Ping
#         * GP2D12
#         * Analog
#         * Digital
#         * PololuMotorCurrent
#         * PhidgetsVoltage
#         * PhidgetsCurrent (20 Amp, DC)

sensors: {
  #motor_current_left:   {pin: 0, type: PololuMotorCurrent, rate: 5},
  #motor_current_right:  {pin: 1, type: PololuMotorCurrent, rate: 5},
  #ir_front_center:      {pin: 2, type: GP2D12, rate: 10},
  #sonar_front_center:   {pin: 5, type: Ping, rate: 10},
  arduino_led:          {pin: 13, type: Digital, rate: 5, direction: output}
}

Example Launch File

<launch>
   <node name="arduino" pkg="ros_arduino_python" type="arduino_node.py" output="screen">
      <rosparam file="$(find ros_arduino_python)/config/my_arduino_params.yaml" command="load" />
   </node>
</launch>

Usage Notes

  • Be sure to put your robot on blocks before first trying the base controller
  • If you mess up your parameters in a given session, just do a:

    rosparam delete /arduino
  • The driver requires Python 2.6.5 or higher and PySerial 2.3 or higher. It has been tested on Ubuntu Linux 10.04 (Maveric) and 11.10 (Oneric).

Report a Bug

https://github.com/hbrobotics/ros_arduino_bridge/issues

Wiki: ros_arduino_python (last edited 2014-03-03 00:37:25 by Patrick Goebel)