Functions
franka_gripper Namespace Reference

Functions

bool grasp (const franka::Gripper &gripper, const GraspGoalConstPtr &goal)
 Calls the libfranka grasp service of the gripper. More...
 
void gripperCommandExecuteCallback (const franka::Gripper &gripper, const GraspEpsilon &grasp_epsilon, double default_speed, actionlib::SimpleActionServer< control_msgs::GripperCommandAction > *action_server, const control_msgs::GripperCommandGoalConstPtr &goal)
 Wraps the execution of a gripper command action to catch exceptions and report results. More...
 
bool homing (const franka::Gripper &gripper, const HomingGoalConstPtr &)
 Calls the libfranka homing service of the gripper. More...
 
bool move (const franka::Gripper &gripper, const MoveGoalConstPtr &goal)
 Calls the libfranka move service of the gripper. More...
 
bool stop (const franka::Gripper &gripper, const StopGoalConstPtr &)
 Calls the libfranka stop service of the gripper to stop applying force. More...
 
bool updateGripperState (const franka::Gripper &gripper, franka::GripperState *state)
 Reads a gripper state if possible. More...
 

Function Documentation

bool franka_gripper::grasp ( const franka::Gripper gripper,
const GraspGoalConstPtr &  goal 
)

Calls the libfranka grasp service of the gripper.

An object is considered grasped if the distance $d$ between the gripper fingers satisfies $(\text{width} - \text{epsilon_inner}) < d < (\text{width} + \text{epsilon_outer})$.

Parameters
[in]gripperA gripper instance to execute the command
[in]goalA grasp goal with target width, epsilon_inner, epsilon_outer, velocity and effort
Returns
True if an object has been grasped, false otherwise.

Definition at line 89 of file franka_gripper.cpp.

void franka_gripper::gripperCommandExecuteCallback ( const franka::Gripper gripper,
const GraspEpsilon &  grasp_epsilon,
double  default_speed,
actionlib::SimpleActionServer< control_msgs::GripperCommandAction > *  action_server,
const control_msgs::GripperCommandGoalConstPtr &  goal 
)

Wraps the execution of a gripper command action to catch exceptions and report results.

Note
For compatibility with current MoveIt! behavior, the given goal's command position is multiplied by a factor of 2 before being commanded to the gripper!
Parameters
[in]gripperA pointer to a franka gripper
[in]default_speedThe default speed for a gripper action
[in]grasp_epsilonThe epsilon window of the grasp.
[in]action_serverA pointer to a gripper action server
[in]goalA gripper action goal

Definition at line 30 of file franka_gripper.cpp.

bool franka_gripper::homing ( const franka::Gripper gripper,
const HomingGoalConstPtr &   
)

Calls the libfranka homing service of the gripper.

Parameters
[in]gripperA gripper instance to execute the command
Returns
True if command was successful, false otherwise.

Definition at line 81 of file franka_gripper.cpp.

bool franka_gripper::move ( const franka::Gripper gripper,
const MoveGoalConstPtr &  goal 
)

Calls the libfranka move service of the gripper.

Parameters
[in]gripperA gripper instance to execute the command
[in]goalA move goal with target width and velocity
Returns
True if command was successful, false otherwise.

Definition at line 77 of file franka_gripper.cpp.

bool franka_gripper::stop ( const franka::Gripper gripper,
const StopGoalConstPtr &   
)

Calls the libfranka stop service of the gripper to stop applying force.

Parameters
[in]gripperA gripper instance to execute the command
Returns
True if command was successful, false otherwise.

Definition at line 85 of file franka_gripper.cpp.

bool franka_gripper::updateGripperState ( const franka::Gripper gripper,
franka::GripperState state 
)

Reads a gripper state if possible.

Parameters
[in]stateA gripper state to update
[in]gripperA pointer to a franka gripper
Returns
True if update was successful, false otherwise.

Definition at line 20 of file franka_gripper.cpp.



franka_gripper
Author(s): Franka Emika GmbH
autogenerated on Fri Oct 23 2020 03:47:02