ActivMedia mobile robots. More...

ActivMedia mobile robots.

Many robots made by ActivMedia, such as the Pioneer series and the AmigoBot, are controlled by a microcontroller that runs a special embedded operating system called P2OS (aka AROS, PSOS). The host computer talks to the P2OS microcontroller over a standard RS232 serial line. This driver offer access to the various P2OS-mediated devices, logically splitting up the devices' functionality.

Compile-time dependencies
  • none
Provides

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

Supported configuration requests
  • "odometry" position2d :
    • PLAYER_POSITION2D_REQ_SET_ODOM
    • PLAYER_POSITION2D_REQ_MOTOR_POWER
    • PLAYER_POSITION2D_REQ_RESET_ODOM
    • PLAYER_POSITION2D_REQ_GET_GEOM
    • PLAYER_POSITION2D_REQ_VELOCITY_MODE
  • sonar :
    • PLAYER_SONAR_REQ_POWER
    • PLAYER_SONAR_REQ_GET_GEOM
  • bumper :
    • PLAYER_BUMPER_REQ_GET_GEOM
  • blobfinder :
    • PLAYER_BLOBFINDER_REQ_SET_COLOR
    • PLAYER_BLOBFINDER_REQ_SET_IMAGER_PARAMS
Configuration file options
  • port (string)
    • Default: "/dev/ttyS0"
  • use_tcp (boolean)
    • Defaut: 0
    • Set to 1 if a TCP connection should be used instead of serial port (e.g. Amigobot with ethernet-serial bridge device attached)
  • tcp_remote_host (string)
    • Default: "localhost"
    • Remote hostname or IP address to connect to if using TCP
  • tcp_remote_port (integer)
    • Default: 8101
    • Remote port to connect to if using TCP
    • Serial port used to communicate with the robot.
  • radio (integer)
    • Default: 0
    • Nonzero if a radio modem is being used; zero for a direct serial link. (a radio modem is different from and older than the newer ethernet-serial bridge used on newer Pioneers and Amigos)
  • bumpstall (integer)
    • Default: -1
    • Determine whether a bumper-equipped robot stalls when its bumpers are pressed. Allowed values are:
      • -1 : Don't change anything; the bumper-stall behavior will be determined by the BumpStall value stored in the robot's FLASH.
      • 0 : Don't stall.
      • 1 : Stall on front bumper contact.
      • 2 : Stall on rear bumper contact.
      • 3 : Stall on either bumper contact.
  • pulse (float)
    • Default: -1
    • Specify a pulse for keeping the robot alive. Pioneer robots have a built-in watchdog in the onboard controller. After a timeout period specified in the robot's FLASH, if no commands have been received from the player server, the robot will stop. By specifying a positive value here, the Player server will send a regular pulse command to the robot to let it know the client is still alive. The value should be in seconds, with decimal places allowed (eg 0.5 = half a second). Note that if this value is greater than the Pioneer's onboard value, it will still time out.
    • Specifying a value of -1 turns off the pulse, meaning that if you do not send regular commands from your client program, the robot's onboard controller will time out and stop.
    • WARNING: Overriding the onboard watchdog is dangerous! Specifying -1 and writing your client appropriately is definitely the preffered option!
  • joystick (integer)
    • Default: 0
    • Use direct joystick control
  • direct_wheel_vel_control (integer)
    • Default: 1
    • Send direct wheel velocity commands to P2OS (as opposed to sending translational and rotational velocities and letting P2OS smoothly achieve them).
  • max_xspeed (length)
    • Default: 0.5 m/s
    • Maximum translational velocity
  • max_yawspeed (angle)
    • Default: 100 deg/s
    • Maximum rotational velocity
  • max_xaccel (length)
    • Default: 0
    • Maximum translational acceleration, in length/sec/sec; nonnegative. Zero means use the robot's default value.
  • max_xdecel (length)
    • Default: 0
    • Maximum translational deceleration, in length/sec/sec; nonpositive. Zero means use the robot's default value.
  • max_yawaccel (angle)
    • Default: 0
    • Maximum rotational acceleration, in angle/sec/sec; nonnegative. Zero means use the robot's default value.
  • rot_kp (integer)
    • Default: -1
    • Rotational PID setting; proportional gain. Negative means use the robot's default value.
    • Requires P2OS1.M or above
  • rot_kv (integer)
    • Default: -1
    • Rotational PID setting; derivative gain. Negative means use the robot's default value.
    • Requires P2OS1.M or above
  • rot_ki (integer)
    • Default: -1
    • Rotational PID setting; integral gain. Negative means use the robot's default value.
    • Requires P2OS1.M or above
  • trans_kp (integer)
    • Default: -1
    • Translational PID setting; proportional gain. Negative means use the robot's default value.
    • Requires P2OS1.M or above
  • trans_kv (integer)
    • Default: -1
    • Translational PID setting; derivative gain. Negative means use the robot's default value.
    • Requires P2OS1.M or above
  • trans_ki (integer)
    • Default: -1
    • Translational PID setting; integral gain. Negative means use the robot's default value.
    • Requires P2OS1.M or above
  • max_yawdecel (angle)
    • Default: 0
    • Maximum rotational deceleration, in angle/sec/sec; nonpositive. Zero means use the robot's default value.
  • use_vel_band (integer)
    • Default: 0
    • Use velocity bands
  • aa_basepos (3 floats)
    • Default: (0.105, 0, 0.3185)
    • Position of the base of the arm from the robot centre in metres.
  • aa_baseorient (3 floats)
    • Default: 0, 0, 0
    • Orientation of the base of the arm from the robot centre in radians.
  • aa_offsets (6 floats)
    • Default: (0.06875, 0.16, 0, 0.13775, 0.11321, 0)
    • Offsets for the actarray. Taken from current actuator to next actuator. Each offset is a straight line, not measured per axis.
  • aa_orients (3x6 floats)
    • Default: all zero
    • Orientation of each actuator when it is at 0. Measured by taking a line from this actuator to the next and measuring its angles about the 3 axes of the previous actuator's coordinate space.
    • Each set of three values is a single orientation.
  • aa_axes (3x6 floats)
    • Default: ((0,0,-1), (0,-1,0), (0,-1,0), (1,0,0), (0,1,0), (0,0,1))
    • The axis of rotation for each joint in the actarray.
    • Each set of three values is a vector along the axis of rotation.
  • limb_pos (3 floats)
    • Default: (0.105, 0, 0.3185)
    • Position of the base of the arm from the robot centre in metres.
  • limb_links (5 floats)
    • Default: (0.06875, 0.16, 0, 0.13775, 0.11321)
    • Offset from previous joint to this joint in metres. e.g. the offset from joint 0 to joint 1 is 0.06875m, and from joint 1 to joint 2 is 0.16m.
    • The default is correct for the standard Pioneer arm at time of writing.
  • limb_offsets (5 floats, metres)
    • Default: (0, 0, 0, 0, 0)
    • Angular offset of each joint from desired position to actual position (calibration data).
    • Possibly taken by commanding joints to 0rad with actarray interface, then measuring their actual angle.
  • gripper_pose (6 floats - 3 in metres, 3 in rads)
    • Default: (0, 0, 0, 0, 0, 0)
    • 3D pose of the standard gripper
  • gripper_outersize (3 floats, metres)
    • Default: (0.315, 0.195, 0.035)
    • Size of the outside of the standard gripper
  • gripper_innersize (3 floats, metres)
    • Default: (0.205, 0.095, 1.0)
    • Size of the inside of the standard gripper's fingers when fully open, i.e. the largest object it can pick up.
  • armgrip_outersize (3 floats, metres)
    • Default: (0.09, 0.09, 0.041)
    • Size of the outside of the arm's gripper
  • armgrip_innersize (3 floats, metres)
    • Default: (0.054, 0.025, 1.0)
    • Size of the inside of the arm's gripper (largest object it can hold)
  • ignore_checksum (boolean)
    • Default: False (no effect)
    • If set to True, the checksum will be ignored
Example
driver
(
  name "p2os"
  provides ["odometry::position:0" "compass::position:1" "sonar:0" "power:0"]
)
Author
Brian Gerkey, Kasper Stoy, James McKenna

Last updated 12 September 2005 21:38:45