Only released in EOL distros:  

wheeled_robin: wheeled_robin_bringup | wheeled_robin_description | wheeled_robin_driver | wheeled_robin_node

Package Summary

The wheeled_robin_node package

Documentation

To start the WheeledRobin driver node use the launch files in wheeled_robin_bringup.

Nodes

wheeled_robin_node

ROS bindings for the WheeledRobin driver (wheeled_robin_driver). This is based on create_node driver by OSRF.

Subscribed Topics

cmd_vel (geometry_msgs/Twist)
  • Desired velocity for WheeledRobin (x, theta)

Published Topics

odom (nav_msgs/Odometry)
  • Odometry of WheeledRobin.
joint_states (sensor_msgs/JointState)
  • Joint State for the left and right wheel.
~sensor_state (wheeled_robin_node/WheeledRobinSensorState)
  • State of the WheeledRobin sensors.
diagnostics (diagnostic_msgs/DiagnosticArray)
  • Diagnostic information for WheeledRobin.

Services

~set_operation_mode (wheeled_robin_node/SetWheeledRobinMode)
  • Sets the operation mode of WheeledRobin.
~set_digital_outputs (wheeled_robin_node/SetDigitalOutputs)
  • Sets the digital outputs of WheeledRobin.

Parameters

~update_rate (double, default: 100.0)
  • Polling rate for the WheeledRobin. Choices: 5 - 1000 Hz
~drive_mode (string, default: 'drive')
  • The possible drive modes. While 'drive' takes a geometry_msgs/Twist message and sends it directly to the robot, 'direct_drive' takes a geometry_msgs/Twist message, calculates wheels speeds and sends them to the robot. Choices: 'drive' or 'direct_drive'
~cmd_vel_timeout (double, default: 0.6)
  • How long to wait before timing out on a velocity command. Choices: 0.0 - 1.0
~odom_angular_scale_correction (double, default: 1.0)
  • A correction applied to the computation of the rotation in the odometry. Choices: 0.0 - 3.0
~odom_linear_scale_correction (double, default: 1.0)
  • A correction applied to the computation of the translation in odometry. Choices: 0.0 - 3.0
~min_abs_yaw_vel (double, default: None)
  • Minimum angular velocity of the WheeledRobin. Choices: 0.0 - 3.0
~max_abs_yaw_vel (double, default: None)
  • Maximum angular velocity of the WheeledRobin. Choices: 0.0 - 3.0
~port (string, default: /dev/ttyUSB0)
  • Serial port where WheeledRobin is connected to.
~publish_tf (bool, default: False)
  • Publish Transformations.
~odom_frame (string, default: odom)
  • Name of the odom frame (used while publishing TF).
~base_footprint_frame (string, default: base_footprint)
  • Name of the base_footprint frame (used while publishing TF).
~base_link_frame (string, default: base_link)
  • Name of the base_link frame (used while publishing TF).
~operation_mode (integer, default: 3)
  • Operation mode of WheeledRobin used while driving. Choices: 2 or 3

Provided tf Transforms

odombase_footprint
  • odom frame is set with '~odom_frame' parameter, base_footprint frame is set with '~base_footprint_frame' parameter. Depends on the odometry of WheeledRobin
base_footprintbase_link
  • base_footprint frame is set with '~base_footprint_fra,e' parameter, base_link frame is set with '~base_link_frame' parameter. Depends on the pitch angle of WheeledRobin

Wiki: wheeled_robin_node (last edited 2013-11-14 10:41:07 by KlemensSpringer)