Interface with the robot gripper. Because gripper is also a type of device, this API uses the same underlying infrastructure as rdk::Device, but with functions tailored specifically for gripper controls.
More...
#include <gripper.hpp>
|
| Gripper (const Robot &robot) |
| [Non-blocking] Create an instance and initialize gripper control interface. More...
|
|
void | Enable (const std::string &name) |
| [Blocking] Enable the specified gripper as a device, same as Device::Enable(). More...
|
|
void | Disable () |
| [Blocking] Disable the currently enabled gripper, similar to Device::Disable(). More...
|
|
void | Init () |
| [Blocking] Manually trigger the initialization of the enabled gripper. This step is not needed for grippers that automatically initialize upon power-on. More...
|
|
void | Grasp (double force) |
| [Blocking] Grasp with direct force control. Requires the mounted gripper to support direct force control. More...
|
|
void | Move (double width, double velocity, double force_limit=0) |
| [Blocking] Move the gripper fingers with position control. More...
|
|
void | Stop () |
| [Blocking] Stop the gripper and hold its current finger width. More...
|
|
const GripperParams | params () const |
| [Non-blocking] Parameters of the currently enabled gripper. More...
|
|
const GripperStates | states () const |
| [Non-blocking] Current states data of the enabled gripper. More...
|
|
Interface with the robot gripper. Because gripper is also a type of device, this API uses the same underlying infrastructure as rdk::Device, but with functions tailored specifically for gripper controls.
Definition at line 77 of file gripper.hpp.
◆ Gripper()
flexiv::rdk::Gripper::Gripper |
( |
const Robot & |
robot | ) |
|
[Non-blocking] Create an instance and initialize gripper control interface.
- Parameters
-
- Exceptions
-
std::runtime_error | if the initialization sequence failed. |
◆ Disable()
void flexiv::rdk::Gripper::Disable |
( |
| ) |
|
[Blocking] Disable the currently enabled gripper, similar to Device::Disable().
- Exceptions
-
std::logic_error | if no gripper device is enabled. |
std::runtime_error | if failed to deliver the request to the connected robot. |
- Note
- This function blocks until the request is successfully delivered.
◆ Enable()
void flexiv::rdk::Gripper::Enable |
( |
const std::string & |
name | ) |
|
[Blocking] Enable the specified gripper as a device, same as Device::Enable().
- Parameters
-
[in] | name | Name of the gripper device to enable, must be an existing one. |
- Exceptions
-
std::logic_error | if the specified gripper device does not exist or a gripper is already enabled. |
std::runtime_error | if failed to deliver the request to the connected robot or failed to sync gripper parameters. |
- Note
- This function blocks until the request is successfully delivered.
-
There can only be one enabled gripper at a time, call Disable() on the currently enabled gripper before enabling another gripper.
- Warning
- There's no enforced check on whether the enabled device is a gripper or not. Using this API on a non-gripper device will likely lead to undefined behaviors.
◆ Grasp()
void flexiv::rdk::Gripper::Grasp |
( |
double |
force | ) |
|
[Blocking] Grasp with direct force control. Requires the mounted gripper to support direct force control.
- Parameters
-
[in] | force | Target gripping force. Positive: closing force, negative: opening force [N]. |
- Exceptions
-
std::logic_error | if no gripper device is enabled. |
std::runtime_error | if failed to deliver the request to the connected robot. |
- Note
- This function blocks until the request is successfully delivered.
- Warning
- Target inputs outside the valid range (see params()) will be saturated.
◆ Init()
void flexiv::rdk::Gripper::Init |
( |
| ) |
|
[Blocking] Manually trigger the initialization of the enabled gripper. This step is not needed for grippers that automatically initialize upon power-on.
- Exceptions
-
std::logic_error | if no gripper device is enabled. |
std::runtime_error | if failed to deliver the request to the connected robot. |
- Note
- This function blocks until the request is successfully delivered.
- Warning
- This function does not wait for the initialization sequence to finish, the user may need to implement wait after calling this function before commanding the gripper.
◆ Move()
void flexiv::rdk::Gripper::Move |
( |
double |
width, |
|
|
double |
velocity, |
|
|
double |
force_limit = 0 |
|
) |
| |
[Blocking] Move the gripper fingers with position control.
- Parameters
-
[in] | width | Target opening width [m]. |
[in] | velocity | Closing/opening velocity, cannot be 0 [m/s]. |
[in] | force_limit | Maximum output force during movement [N]. If not specified, default force limit of the mounted gripper will be used. |
- Exceptions
-
std::logic_error | if no gripper device is enabled. |
std::runtime_error | if failed to deliver the request to the connected robot. |
- Note
- This function blocks until the request is successfully delivered.
- Warning
- Target inputs outside the valid range (see params()) will be saturated.
◆ params()
[Non-blocking] Parameters of the currently enabled gripper.
- Returns
- GripperParams value copy.
◆ states()
[Non-blocking] Current states data of the enabled gripper.
- Returns
- GripperStates value copy.
- Note
- Real-time (RT).
◆ Stop()
void flexiv::rdk::Gripper::Stop |
( |
| ) |
|
[Blocking] Stop the gripper and hold its current finger width.
- Exceptions
-
std::logic_error | if no gripper device is enabled. |
std::runtime_error | if failed to deliver the request to the connected robot. |
- Note
- This function blocks until the request is successfully delivered.
The documentation for this class was generated from the following file: