Interface with the robot gripper.
More...
#include <gripper.hpp>
|
| Gripper (const Robot &robot) |
| [Non-blocking] Create an instance and initialize gripper control interface. More...
|
|
void | Init () |
| [Blocking] Initialize the gripper. More...
|
|
void | Grasp (double force) |
| [Non-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) |
| [Non-blocking] Move the gripper fingers with position control. More...
|
|
void | Stop () |
| [Blocking] Stop the gripper. More...
|
|
bool | moving () const |
| [Non-blocking] Whether the gripper fingers are moving. More...
|
|
const GripperStates | states () const |
| [Non-blocking] Access the current gripper states. More...
|
|
Interface with the robot gripper.
- Examples
- basics6_gripper_control.cpp.
Definition at line 19 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. |
◆ Grasp()
void flexiv::rdk::Gripper::Grasp |
( |
double |
force | ) |
|
[Non-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]. |
- Note
- Applicable control modes: all modes except IDLE.
- Exceptions
-
std::logic_error | if robot is not in the correct control mode. |
- Warning
- Target inputs outside the valid range (specified in gripper's configuration file) will be saturated.
- Examples
- basics6_gripper_control.cpp.
◆ Init()
void flexiv::rdk::Gripper::Init |
( |
| ) |
|
[Blocking] Initialize the gripper.
- Note
- Applicable control modes: all modes except IDLE.
-
This function blocks until the initialization is finished.
- Examples
- basics6_gripper_control.cpp.
◆ Move()
void flexiv::rdk::Gripper::Move |
( |
double |
width, |
|
|
double |
velocity, |
|
|
double |
force_limit = 0 |
|
) |
| |
[Non-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. |
- Note
- Applicable control modes: all modes except IDLE.
- Exceptions
-
std::logic_error | if robot is not in the correct control mode. |
- Warning
- Target inputs outside the valid range (specified in gripper's configuration file) will be saturated.
- Examples
- basics6_gripper_control.cpp.
◆ moving()
bool flexiv::rdk::Gripper::moving |
( |
| ) |
const |
◆ states()
◆ Stop()
void flexiv::rdk::Gripper::Stop |
( |
| ) |
|
[Blocking] Stop the gripper.
- Note
- Applicable control modes: all modes.
-
This function blocks until the gripper control is transferred back to plan/primitive.
- Examples
- basics6_gripper_control.cpp.
The documentation for this class was generated from the following file: