Erratic platform driver

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:

  • "odometry" interface_position2d
    • This interface returns odometry data, and accepts velocity commands.
  • interface_power
    • Returns the current battery voltage (12 V when fully charged).
  • interface_aio
    • Returns data from analog and digital input pins
  • interface_ir
    • Returns ranges from IR sensors, assuming they're connected to the analog input pins
  • interface_sonar
    • Returns ranges from sonar sensors
  • interface_ptz : control of the servos that pan and tilt
Supported configuration requests
  • "odometry" interface_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
  • interface_ir :
    • PLAYER_IR_REQ_POSE
  • interface_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