Flexiv RDK APIs  1.7.0
Public Member Functions | List of all members
flexiv::rdk::Gripper Class Reference

Interface to control the gripper installed on the robot. Because gripper is also a type of robot device, this API uses the same underlying infrastructure as rdk::Device, but with functions tailored specifically for gripper controls. More...

#include <gripper.hpp>

Public Member Functions

 Gripper (const Robot &robot)
 [Non-blocking] Instantiate the gripper control interface. More...
 
void Enable (const std::string &name)
 [Blocking] Enable the specified gripper as a robot device. More...
 
void Disable ()
 [Blocking] Disable the currently enabled gripper. 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. This function requires the enabled gripper to support direct force control. More...
 
void Move (double width, double velocity, double force_limit)
 [Blocking] Move the gripper fingers with position control. More...
 
void Stop ()
 [Blocking] Stop the gripper and hold its current finger width. More...
 
GripperParams params () const
 [Non-blocking] Parameters of the currently enabled gripper. More...
 
GripperStates states () const
 [Non-blocking] Current states data of the enabled gripper. More...
 

Detailed Description

Interface to control the gripper installed on the robot. Because gripper is also a type of robot device, this API uses the same underlying infrastructure as rdk::Device, but with functions tailored specifically for gripper controls.

Definition at line 76 of file gripper.hpp.

Constructor & Destructor Documentation

◆ Gripper()

flexiv::rdk::Gripper::Gripper ( const Robot robot)

[Non-blocking] Instantiate the gripper control interface.

Parameters
[in]robotReference to the instance of flexiv::rdk::Robot.
Exceptions
std::runtime_errorif the initialization sequence failed.

Member Function Documentation

◆ Disable()

void flexiv::rdk::Gripper::Disable ( )

[Blocking] Disable the currently enabled gripper.

Exceptions
std::logic_errorif no gripper is enabled.
std::runtime_errorif 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 robot device.

Parameters
[in]nameName of the gripper to enable.
Exceptions
std::invalid_argumentif the specified gripper does not exist.
std::logic_errorif a gripper is already enabled.
std::runtime_errorif 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 function to enable a non-gripper device will likely lead to undefined behaviors.

◆ Grasp()

void flexiv::rdk::Gripper::Grasp ( double  force)

[Blocking] Grasp with direct force control. This function requires the enabled gripper to support direct force control.

Parameters
[in]forceTarget gripping force. Positive: closing force, negative: opening force. Valid range: [GripperParams::min_force, GripperParams::max_force]. Unit: \( [N] \).
Exceptions
std::invalid_argumentif [force] is outside the valid range.
std::logic_errorif no gripper is enabled.
std::runtime_errorif failed to deliver the request to the connected robot.
Note
This function blocks until the request is successfully delivered.

◆ 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_errorif no gripper is enabled.
std::runtime_errorif 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 
)

[Blocking] Move the gripper fingers with position control.

Parameters
[in]widthTarget opening width. Valid range: [GripperParams::min_width, GripperParams::max_width]. Unit: \( [m] \).
[in]velocityClosing/opening velocity, cannot be 0. Valid range: [GripperParams::min_vel, GripperParams::max_vel]. Unit: \( [m/s] \).
[in]force_limitMaximum contact force during movement. Valid range: [GripperParams::min_force, GripperParams::max_force]. Unit: \( [N] \).
Exceptions
std::invalid_argumentif any input parameter is outside its valid range.
std::logic_errorif no gripper is enabled.
std::runtime_errorif failed to deliver the request to the connected robot.
Note
This function blocks until the request is successfully delivered.

◆ params()

GripperParams flexiv::rdk::Gripper::params ( ) const

[Non-blocking] Parameters of the currently enabled gripper.

Returns
GripperParams value copy.

◆ states()

GripperStates flexiv::rdk::Gripper::states ( ) const

[Non-blocking] Current states data of the enabled gripper.

Returns
GripperStates value copy.

◆ Stop()

void flexiv::rdk::Gripper::Stop ( )

[Blocking] Stop the gripper and hold its current finger width.

Exceptions
std::logic_errorif no gripper is enabled.
std::runtime_errorif 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: