|
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
- Provides
The p2os driver provides the following device interfaces, some of them named:
- "odometry" position
- This interface returns odometry data, and accepts velocity commands.
- "compass" position
- This interface returns compass data (if equipped).
- "gyro" position
- This interface returns gyroscope data (if equipped).
- power
- Returns the current battery voltage (12 V when fully charged).
- sonar
- Returns data from sonar arrays (if equipped)
- aio
- Returns data from analog I/O ports (if equipped)
- dio
- Returns data from digital I/O ports (if equipped)
- gripper
- Controls gripper (if equipped)
- bumper
- Returns data from bumper array (if equipped)
- blobfinder
- Controls a CMUCam2 connected to the AUX port on the P2OS board (if equipped).
- sound
- Controls the sound system of the AmigoBot, which can play back recorded wav files.
- Supported configuration requests
- "odometry" position:
- 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
- sonar:
- PLAYER_SONAR_POWER_REQ
- PLAYER_SONAR_GET_GEOM_REQ
- blobfinder
- PLAYER_BLOBFINDER_SET_COLOR_REQ
- PLAYER_BLOBFINDER_SET_IMAGER_PARAMS_REQ
- Configuration file options
- port (string)
- Default: "/dev/ttyS0"
- 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.
- 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.
- 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.
- 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
- Example
driver
(
name "p2os"
provides ["odometry::position:0" "compass::position:1" "sonar:0" "power:0"]
)
- Authors
Brian Gerkey, Kasper Stoy, James McKenna
Generated on Tue May 3 14:16:12 2005 for Player by 1.3.6
|