Only released in EOL distros:  

Package Summary

ROS Package for the Element microcontroller made by cmRobot.

Package Summary

ROS Package for the Element microcontroller made by cmRobot.

Package Summary

ROS Package for the Element microcontroller made by cmRobot.

Overview

The Element package consists of a Python driver and ROS node for the Element microcontroller made by cmRobot. The Element connects to a PC or SBC using either a USB port, XBEE radios or TTL.

float

Features

  • Direct support for a wide variety of commonly used sensors including sonar (Ping, MaxEZ, SRF04, SRF05, SRF08, SRF10), infrared (Sharp GP2D12), temperature, current, and voltage (Phidgets), speech (Devantech SP03), compass (Devantech CMPS03), as well as generic digital and analog sensors.
  • Onboard PID controller and dual H-Bridges for driving a differential drive robot.
  • Support for attaching up to six hobby servos.

Element Node

element-node.py

A ROS node for the Element microcontroller made by cmRobot. Uses a multi-threaded queue so that each sensor can be polled at its own rate (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 10 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.
~sensors (element/SensorState)
  • An array of sensor names and values.
~sensor/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

~SetServo (element/SetServo)
  • Set the target position of servo on pin 'id' to 'value'.
~GetAnalog (element/GetAnalog)
  • Get the value from an analog sensor on pin 'id'.
~Voltage (element/Voltage)
  • Return the voltage on the Element's main terminals.
~Ping (element/Ping)
  • Query a Ping sonar sensor on digital pin 'id'.
~GP2D12 (element/GP2D12)
  • Query a GP2D12 IR sensor on analog pin 'id'.
~PhidgetsTemperature (element/PhidgetsTemperature)
  • Query a Phidgets Temperature sensor on analog pin 'id'.
~PhidgetsVoltage (element/PhidgetsVoltage)
  • Query a Phidgets voltage sensor on analog pin 'id'.
~PhidgetsCurrent (element/PhidgetsCurrent)
  • Query a Phidgets current sensor on analog pin 'id'.
~Rotate (element/Rotate)
  • Rotate the robot base through 'angle' radians at 'velocity' rad/s.
~TravelDistance (element/TravelDistance)
  • Move the robot forward or backward through 'distance' meters at 'velocity' m/s.
~Speak (element/SP03)
  • Use the SP03 text-to-speech chip to speak a phrase given as a string

Parameters

~port (str, default: /dev/ttyUSB0)
  • Serial port.
~baud (int, default: 19200)
  • Baud rate.
~timeout (float, default: 0.5)
  • Timeout for serial port in seconds.
~publish_sensors (bool, default: False)
  • Whether or not to automatically publish sensor data.
~sensor_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 PID base controller.
~units (int, default: 0)
  • Measurement units to use: 0 = metric, 1 = English, 2 = raw. For use with ROS, it is recommended to always leave this set to 0 for metric.
~wheel_diameter (float, default: none)
  • Wheel diameter in meters.
~wheel_track (float, default: none)
  • Wheel track in meters.
~encoder_type (int, default: 1)
  • Encoder type: 0 = single, 1 = quadrature
~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.
~init_pid (bool, default: False)
  • Whether or not to write the PID parameters to the Element firmware.
~VPID_P (int, default: none)
  • Velocity Proportial PID parameter.
~VPID_I (int, default: none)
  • Velocity Integral PID parameter.
~VPID_D (int, default: none)
  • Velocity Derivative PID parameter.
~VPID_L (int, default: none)
  • Velocity Loop PID parameter.
~DPID_P (int, default: none)
  • Distance Proportial PID parameter.
~DPID_I (int, default: none)
  • Distance Integral PID parameter.
~DPID_D (int, default: none)
  • Distance Derivative PID parameter.
~DPID_L (int, default: none)
  • Distance Loop PID parameter.
~base_controller_rate (int, default: 10)
  • Rate to publish odometry information.
~analog (dict, default: None)
  • Dictionary of analog sensors
~digital (dict, default: None)
  • Dictionary of digital sensors
~maxez1 (dict, default: None)
  • Dictionary of MaxEZ1 sensors

Provided tf Transforms

odombase_link
  • Transform needed for navigation.

Configuration

The Element node is configured using a YAML file specifying the required parameters. A sample parameter file called element_params.yaml is included in the distribution in the config directory and is shown below. Note that many of the parameters are commented out and must be set and un-commented before you can use the node with your Element.

Current valid sensor types names (case-sensitive):

port: /dev/ttyUSB0
baud: 19200
timeout: 1
sensor_rate: 10
#use_base_controller: True
#base_controller_rate: 10
#wheel_diameter: <fill in and uncomment for your robot>
#wheel_track: <fill in and uncomment for your robot>
#encoder_type: 1
#encoder_resolution: <fill in and uncomment for your robot>
#gear_reduction: <fill in and uncomment for your robot>
#motors_reversed: False
#init_pid: True
#units: 0
#VPID_P: <fill in and uncomment for your robot>
#VPID_I: <fill in and uncomment for your robot>
#VPID_D: <fill in and uncomment for your robot>
#VPID_L: <fill in and uncomment for your robot>
#DPID_P: <fill in and uncomment for your robot>
#DPID_I: <fill in and uncomment for your robot>
#DPID_D: <fill in and uncomment for your robot>
#DPID_A: <fill in and uncomment for your robot>
#DPID_B: <fill in and uncomment for your robot>

publish_sensors: True

# Examples only - change accordingly for your robot.
analog: { voltage: {pin: 5, type: Voltage, rate: 1}, drive_current: {pin: 1, type: PhidgetsCurrent, rate: 1}, light_sensor: {pin: 2, type: Analog, rate: 10} }
#digital: { base_sonar: {pin: 5, type: Ping, rate: 1} }

Example Launch File

<launch>
   <node name="element" pkg="element" type="element_node.py" output="screen">
   <rosparam file="$(find my_robot)/config/element_params.yaml" command="load" />
   </node>
</launch>

Usage Notes

  • If you mess up your parameters in a given session, just do a:

    rosparam delete /element
  • Try to keep the sensor and PID polling rates relatively low. Something around 10Hz seems ideal although you can try 15-20Hz.
  • Most of the Element functions have been implemented though a few have not been tested since I don't currently have some of the supported sensors. The functions that have NOT been tested are:
    • step (used with a bipolar stepper motor)
    • sweep (also used with a bipolar stepper motor)
    • srf04, srf08 and srf10 (used with a Devantech SRF04, SRF08 and SRF10 sonar sensors)
    • tpa81 (used with the Devantech TPA81 thermopile sensor)
  • 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).

  • The official Element manual can be found at http://www.cmrobot.com/#!element/vstc8=downloads

Wiki: element (last edited 2012-11-15 14:07:56 by Patrick Goebel)