position1d
[Device proxies]
Collaboration diagram for position1d:
|
Detailed Description
The position1d proxy provides an interface to 1 DOF actuator such as a linear or rotational actuator.
Classes | |
| struct | playerc_position1d_t |
| Position1d device data. More... | |
Functions | |
| playerc_position1d_t * | playerc_position1d_create (playerc_client_t *client, int index) |
| Create a position1d device proxy. | |
| void | playerc_position1d_destroy (playerc_position1d_t *device) |
| Destroy a position1d device proxy. | |
| int | playerc_position1d_subscribe (playerc_position1d_t *device, int access) |
| Subscribe to the position1d device. | |
| int | playerc_position1d_unsubscribe (playerc_position1d_t *device) |
| Un-subscribe from the position1d device. | |
| int | playerc_position1d_enable (playerc_position1d_t *device, int enable) |
| Enable/disable the motors. | |
| int | playerc_position1d_get_geom (playerc_position1d_t *device) |
| Get the position1d geometry. | |
| int | playerc_position1d_set_cmd_vel (playerc_position1d_t *device, double vel, int state) |
| Set the target speed. | |
| int | playerc_position1d_set_cmd_pos (playerc_position1d_t *device, double pos, int state) |
| Set the target position. | |
| int | playerc_position1d_set_cmd_pos_with_vel (playerc_position1d_t *device, double pos, double vel, int state) |
| Set the target position with movement velocity -. | |
| int | playerc_position1d_set_odom (playerc_position1d_t *device, double odom) |
| Set the odometry offset. | |
Function Documentation
| int playerc_position1d_get_geom | ( | playerc_position1d_t * | device | ) |
Get the position1d geometry.
The writes the result into the proxy rather than returning it to the caller.
| int playerc_position1d_set_cmd_pos | ( | playerc_position1d_t * | device, | |
| double | pos, | |||
| int | state | |||
| ) |
Set the target position.
-
- pos The position to move to
| int playerc_position1d_set_cmd_pos_with_vel | ( | playerc_position1d_t * | device, | |
| double | pos, | |||
| double | vel, | |||
| int | state | |||
| ) |
Set the target position with movement velocity -.
- pos The position to move to -
- vel The speed at which to move to the position
