[Documentation] [TitleIndex] [WordIndex

  Show 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

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)

Published Topics

/odom (nav_msgs/Odometry) ~sensor_state (ros_arduino_msgs/SensorState) ~sensor/name (sensor_msgs/Range,)

Services

~servo_write (ros_arduino_msgs/ServoWrite) ~servo_read (ros_arduino_msgs/ServoRead) ~digital_set_direction (ros_arduino_msgs/DigitalSetDirection) ~digital_write (ros_arduino_msgs/DigitalWrite)

Parameters

~port (str, default: /dev/ttyUSB0 -- some controllers use /dev/ttyACM0) ~baud (int, default: 57600) ~timeout (float, default: 0.1) ~rate (int, default: 50) ~sensorstate_rate (int, default: 10) ~use_base_controller (bool, default: False) ~base_controller_rate (int, default: 10) ~base_frame (New in Hydro) (string, default: base_link) ~wheel_diameter (float, default: none) ~wheel_track (float, default: none) ~encoder_resolution (int, default: none) ~gear_reduction (float, default: 1.0) ~motors_reversed (bool, default: False) ~Kp (int, default: 20) ~Kd (int, default: 12) ~Ki (int, default: 0) ~Ko (int, default: 50) ~accel_limit (float, default: 0.1) ~sensors (dict, default: None)

Provided tf Transforms

odombase_link

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

Report a Bug

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


2019-07-20 13:07