Only released in EOL distros:  

Package Summary

ROS Package for the Serializer microcontroller made by the Robotics Connection. (As of 2012, the Serializer is now called the Element and is sold by cmRobot.com.)

Package Summary

ROS Package for the Serializer microcontroller made by the Robotics Connection. (As of 2012, the Serializer is now called the Element and is sold by cmRobot.com.)

Package Summary

ROS Package for the Serializer microcontroller made by the Robotics Connection. (As of 2012, the Serializer is now called the Element and is sold by cmRobot.com.)

Overview

The Serializer package consists of a Python driver and ROS node for the Serializer microcontroller made by the Robotics Connection. The Serializer connects to a PC or SBC using either a USB port or XBEE radios.

Serializer Node

serializer-node.py

A ROS node for the Serializer microcontroller made by the Robotics Connection.

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 (serializer/SensorState)
  • An array of sensor names and values.

Services

~SetServo (serializer/SetServo)
  • Set the target position of servo on pin 'id' to 'value'.
~GetAnalog (serializer/GetAnalog)
  • Get the value from an analog sensor on pin 'id'.
~Voltage (serializer/Voltage)
  • Return the voltage on the Serializer's main terminals.
~Ping (serializer/Ping)
  • Query a Ping sonar sensor on digital pin 'id'.
~GP2D12 (serializer/GP2D12)
  • Query a GP2D12 IR sensor on analog pin 'id'.
~PhidgetsTemperature (serializer/PhidgetsTemperature)
  • Query a Phidgets Temperature sensor on analog pin 'id'.
~PhidgetsVoltage (serializer/PhidgetsVoltage)
  • Query a Phidgets voltage sensor on analog pin 'id'.
~PhidgetsCurrent (serializer/PhidgetsCurrent)
  • Query a Phidgets current sensor on analog pin 'id'.
~Rotate (serializer/Rotate)
  • Rotate the robot base through 'angle' radians at 'velocity' rad/s.
~TravelDistance (serializer/TravelDistance)
  • Move the robot forward or backward through 'distance' meters at 'velocity' m/s.

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 poll sensors and publish data.
~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 Serializer 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.

Provided tf Transforms

odombase_link
  • Transform needed for navigation.

Configuration

The recommended way to configure the Serializer node is to use a YAML file specifying the required parameters. A sample parameter file called sample_params.yaml is included in the distribution 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 Serialzier:

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}, drive_current: {pin: 1, type: PhidgetsCurrent}, light_sensor: {pin: 2, type: Analog} }
#digital: { base_sonar: {pin: 5, type: Ping} }

Example Launch File

<launch>
   <node name="serializer" pkg="serializer" type="serializer_node.py" output="screen">
   <rosparam file="$(find my_robot)/params/serializer_params.yaml" command="load" />
   </node>
</launch>

Usage Notes

Wiki: serializer (last edited 2012-11-14 15:23:07 by Patrick Goebel)