Calculates the joint commands for a given End Effector pose using ROBOOP's Inverse Kinematics algorithms. More...
Calculates the joint commands for a given End Effector pose using ROBOOP's Inverse Kinematics algorithms.
The roboopIK driver performs inverse kinematics calculations using the ROBOOP library for a given robot arm's end effector, and sends the resulting joint commands to the appropriate actarray interface. The arm model is specified in the Player configuration file using the Denavit-Hartenberg convention parameters (see http://prt.fernuni-hagen.de/lehre/KURSE/PRT001/course_main/node15.html for more details).
When a positioning command of the limb is received via PLAYER_LIMB_CMD_SETPOSITION or PLAYER_LIMB_CMD_SETPOSE, the driver computes the joint commands and sends them in ascending order (base to end effector) to the actarray interface using PLAYER_ACTARRAY_CMD_POS.
When a homing command of the limb is received via PLAYER_LIMB_CMD_HOME, the driver will send a PLAYER_ACTARRAY_CMD_HOME to every joint provided by the actarray interface in descending order (end effector to base).
The driver also computes the current pose of the end effector using forward kinematics (given the current joint positions taken from the actarray interface) and returns it as a data packet.
- Compile-time dependencies
- the ROBOOP library (http://www.cours.polymtl.ca/roboop/)
- Provides
- Requires
- Configuration requests
- PLAYER_LIMB_REQ_SPEED
- Configuration file options
- nr_joints (integer)
- The number of joints that we provide DH parameters for (should be the same as the number of actuators the actarray interface provides).
- jointX_DH (integer tuple)
- [ R/P theta d a alfa th_min th_max ] - DH parameters for joint X
- error_pos (float)
- Default: 0
- User allowed error value in position in degrees. This is needed for joints who do not change their state (eg. they remain idle) when a command is given and the joint is already in that position.
- debug (int)
- Default: 0
- Enable debugging mode (detailed information messages are printed on screen) Valid values: 0 (disabled), 1 (enabled).
- Example
driver ( name "eeDHcontroller" provides ["limb:0"] requires ["actarray:0"] nr_joints 6 # [ R/P theta d a alfa th_min th_max ] joint1_DH [ 0 0 0.180 0 1.57 -1.57 2.0 ] joint2_DH [ 0 0 0.215 0 -1.57 -1.57 1.57 ] joint3_DH [ 0 0 0.0 0 1.57 -1.57 1.57 ] joint4_DH [ 0 0 0.308 0 -1.57 -1.57 1.57 ] joint5_DH [ 0 0 0.0 0 1.57 -2.09 2.09 ] joint6_DH [ 0 0 0.2656 0 0 0 0 ] # Allowed positioning error in degrees error_pos 0.01 # Enable debug mode debug 1 )