limb
[Device proxies]
Collaboration diagram for limb:
Detailed Description
The limb proxy provides an interface to limbs using forward/inverse kinematics, such as the ActivMedia Pioneer Arm.See the Player User Manual for a complete description of the drivers that support this interface.
Classes | |
struct | playerc_limb_t |
Limb device data. More... | |
Functions | |
playerc_limb_t * | playerc_limb_create (playerc_client_t *client, int index) |
Create a limb proxy. | |
void | playerc_limb_destroy (playerc_limb_t *device) |
Destroy a limb proxy. | |
int | playerc_limb_subscribe (playerc_limb_t *device, int access) |
Subscribe to the limb device. | |
int | playerc_limb_unsubscribe (playerc_limb_t *device) |
Un-subscribe from the limb device. | |
int | playerc_limb_get_geom (playerc_limb_t *device) |
Get the limb geometry. | |
int | playerc_limb_home_cmd (playerc_limb_t *device) |
Command the end effector to move home. | |
int | playerc_limb_stop_cmd (playerc_limb_t *device) |
Command the end effector to stop immediatly. | |
int | playerc_limb_setpose_cmd (playerc_limb_t *device, float pX, float pY, float pZ, float aX, float aY, float aZ, float oX, float oY, float oZ) |
Command the end effector to move to a specified pose. | |
int | playerc_limb_setposition_cmd (playerc_limb_t *device, float pX, float pY, float pZ) |
Command the end effector to move to a specified position (ignoring approach and orientation vectors). | |
int | playerc_limb_vecmove_cmd (playerc_limb_t *device, float x, float y, float z, float length) |
Command the end effector to move along the provided vector from its current position for the provided distance. | |
int | playerc_limb_power (playerc_limb_t *device, uint32_t enable) |
Turn the power to the limb on or off. | |
int | playerc_limb_brakes (playerc_limb_t *device, uint32_t enable) |
Turn the brakes of all actuators in the limb that have them on or off. | |
int | playerc_limb_speed_config (playerc_limb_t *device, float speed) |
Set the speed of the end effector (m/s) for all subsequent movement commands. |
Function Documentation
int playerc_limb_get_geom | ( | playerc_limb_t * | device | ) |
Get the limb geometry.
The writes the result into the proxy rather than returning it to the caller.
int playerc_limb_power | ( | playerc_limb_t * | device, | |
uint32_t | enable | |||
) |
Turn the power to the limb on or off.
Be careful when turning power on that the limb is not obstructed from its home position in case it moves to it (common behaviour).