Interface with grippers supported by Flexiv.
More...
#include <Gripper.hpp>
|
| Gripper (const Robot &robot) |
| [Non-blocking] Create a flexiv::Gripper instance and initialize robot gripper control. 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 forceLimit=0) |
| [Blocking] Move the gripper fingers with position control. More...
|
|
void | stop (void) |
| [Blocking] Stop the gripper. More...
|
|
void | getGripperStates (GripperStates &output) |
| [Non-blocking] Get current gripper states. More...
|
|
Interface with grippers supported by Flexiv.
- Examples
- basics6_gripper_control.cpp.
Definition at line 18 of file Gripper.hpp.
◆ Gripper()
flexiv::Gripper::Gripper |
( |
const Robot & |
robot | ) |
|
[Non-blocking] Create a flexiv::Gripper instance and initialize robot gripper control.
- Parameters
-
- Exceptions
-
◆ getGripperStates()
◆ grasp()
void flexiv::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]. |
- Note
- Applicable operation modes: all modes except IDLE.
- Exceptions
-
- Warning
- Target inputs outside the valid range (specified in gripper's configuration file) will be saturated.
-
This function blocks until the request is successfully delivered to the robot.
- Examples
- basics6_gripper_control.cpp.
◆ move()
void flexiv::Gripper::move |
( |
double |
width, |
|
|
double |
velocity, |
|
|
double |
forceLimit = 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] | forceLimit | Maximum output force during movement [N]. If not specified, default force limit of the mounted gripper will be used. |
- Note
- Applicable operation modes: all modes except IDLE.
- Exceptions
-
- Warning
- Target inputs outside the valid range (specified in gripper's configuration file) will be saturated.
-
This function blocks until the request is successfully delivered to the robot.
- Examples
- basics6_gripper_control.cpp.
◆ stop()
void flexiv::Gripper::stop |
( |
void |
| ) |
|
[Blocking] Stop the gripper.
- Note
- Applicable operation modes: all modes.
- Exceptions
-
- Warning
- This function blocks until the request is successfully delivered to the robot and gripper control is transferred back to plan/primitive.
- Examples
- basics6_gripper_control.cpp.
The documentation for this class was generated from the following file: