erratic

Copyright (C) 2006 Videre Design Copyright (C) 2000 Brian Gerkey, Kasper Stoy, Richard Vaughan, & Andrew Howard. More...

Copyright (C) 2006 Videre Design Copyright (C) 2000 Brian Gerkey, Kasper Stoy, Richard Vaughan, & Andrew Howard.

Videre Erratic robot driver for Player

This program is free software; you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation; either version 2 of the License, or (at your option) any later version.

This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.

You should have received a copy of the GNU General Public License along with this program; if not, write to the Free Software Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA This driver is adapted from the p2os driver of player 1.6. Erratic

This driver talks to the embedded computer in the Erratic robot, which mediates communication to the devices of the robot.

Compile-time dependencies
  • none
Provides

The erratic driver provides the following device interfaces, some of them named:

Supported configuration requests
  • "odometry" position2d :
    • PLAYER_POSITION_SET_ODOM_REQ
    • PLAYER_POSITION_MOTOR_POWER_REQ
    • PLAYER_POSITION_RESET_ODOM_REQ
    • PLAYER_POSITION_GET_GEOM_REQ
    • PLAYER_POSITION_VELOCITY_MODE_REQ
  • ir :
    • PLAYER_IR_REQ_POSE
  • sonar :
    • PLAYER_SONAR_GET_GEOM_REQ
Configuration file options
  • port (string)
    • Default: "/dev/ttyS0"
  • direct_wheel_vel_control (integer)
    • Default: 0
    • Send direct wheel velocity commands to Erratic (as opposed to sending translational and rotational velocities and letting Erratic smoothly achieve them).
  • max_trans_vel (length)
    • Default: 0.5 m/s
    • Maximum translational velocity
  • max_rot_vel (angle)
    • Default: 100 deg/s
    • Maximum rotational velocity
  • trans_acc (length)
    • Default: 0
    • Maximum translational acceleration, in length/sec/sec; nonnegative. Zero means use the robot's default value.
  • trans_decel (length)
    • Default: trans_acc
    • Maximum translational deceleration, in length/sec/sec; nonpositive. Zero means use the robot's default value.
  • rot_acc (angle)
    • Default: 0
    • Maximum rotational acceleration, in angle/sec/sec; nonnegative. Zero means use the robot's default value.
  • rot_decel (angle)
    • Default: rot_acc
    • Maximum rotational deceleration, in angle/sec/sec; nonpositive. Zero means use the robot's default value.
  • pid_trans_p (integer)
    • Default: -1
    • Translational PID setting; proportional gain. Negative means use the robot's default value.
  • pid_trans_d (integer)
    • Default: -1
    • Translational PID setting; derivative gain. Negative means use the robot's default value.
  • pid_rot_p (integer)
    • Default: -1
    • Rotational PID setting; proportional gain. Negative means use the robot's default value.
  • pid_rot_d (integer)
    • Default: -1
    • Rotational PID setting; derivative gain. Negative means use the robot's default value.
  • motor_pwm_frequency (integer)
    • Default: -1
    • Frequency of motor PWM. Bounds determined by robot. Negative means use the robot's default value.
  • motor_pwm_max_on (float)
    • Default: 1
    • Maximum motor duty cycle.
  • save_settings_in_robot (integer)
    • Default: 0
    • A value of 1 installs current settings as default values in the robot.
Example
driver
(
  name "erratic"
  plugin "erratic"

  provides [ "position2d:0"
             "power:0"
             "sonar:0"
             "aio:0"
             "ir:0"
             "ptz:0"
             "ptz:1" ]

  port "/dev/erratic"

  max_trans_vel 3
  max_rot_vel 720

  trans_acc 1
  rot_acc 200

  direct_wheel_vel_control 0
)
Author
Joakim Arfvidsson, Brian Gerkey, Kasper Stoy, James McKenna

Last updated 12 September 2005 21:38:45