A multi-jointed limb. More...
Detailed Description
A multi-jointed limb.
The limb interface provides access to a multi-jointed limb
Macro Definition Documentation
◆ PLAYER_LIMB_CMD_HOME
#define PLAYER_LIMB_CMD_HOME 1 |
Command: home (PLAYER_LIMB_CMD_HOME)
Tells the end effector to return to its home position.
Referenced by P2OS::ProcessMessage().
◆ PLAYER_LIMB_CMD_STOP
#define PLAYER_LIMB_CMD_STOP 2 |
Command: stop (PLAYER_LIMB_CMD_STOP)
Tells the limb to stop moving immediatly.
Referenced by P2OS::ProcessMessage().
Typedef Documentation
◆ player_limb_brakes_req_t
typedef struct player_limb_brakes_req player_limb_brakes_req_t |
Request/reply: Brakes.
Turn the brakes of the limb on or off by sending a PLAYER_LIMB_REQ_BRAKES request. Null response
◆ player_limb_data_t
typedef struct player_limb_data player_limb_data_t |
Data: state (PLAYER_LIMB_DATA_STATE)
The limb data packet.
◆ player_limb_geom_req_t
typedef struct player_limb_geom_req player_limb_geom_req_t |
Request/reply: get geometry.
Query geometry by sending a null PLAYER_LIMB_REQ_GEOM reqest.
◆ player_limb_power_req_t
typedef struct player_limb_power_req player_limb_power_req_t |
Request/reply: Power.
Turn the power to the limb by sending a PLAYER_LIMB_REQ_POWER request. Be careful when turning power on that the limb is not obstructed from its home position in case it moves to it (common behaviour). Null reponse
◆ player_limb_setpose_cmd_t
typedef struct player_limb_setpose_cmd player_limb_setpose_cmd_t |
Command: Set end effector pose (PLAYER_LIMB_CMD_SETPOSE)
Provides a fully-described pose (position, normal vector and orientation vector) for the end effector to move to.
◆ player_limb_setposition_cmd_t
typedef struct player_limb_setposition_cmd player_limb_setposition_cmd_t |
Command: Set end effector position (PLAYER_LIMB_CMD_SETPOSITION)
Set the position of the end effector without worrying about a specific orientation.
◆ player_limb_speed_req_t
typedef struct player_limb_speed_req player_limb_speed_req_t |
Request/reply: Speed.
Set the speed of the end effector for all subsequent movements by sending a PLAYER_LIMB_REQ_SPEED request. Null response.
◆ player_limb_vecmove_cmd_t
typedef struct player_limb_vecmove_cmd player_limb_vecmove_cmd_t |
Command: Vector move the end effector (PLAYER_LIMB_CMD_VECMOVE)
Move the end effector along the provided vector from its current position for the provided distance.