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... | |
| 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
between the gripper fingers satisfies
.
| [in] | gripper | A gripper instance to execute the command |
| [in] | goal | A grasp goal with target width, epsilon_inner, epsilon_outer, velocity and effort |
Definition at line 94 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.
| [in] | gripper | A pointer to a franka gripper |
| [in] | default_speed | The default speed for a gripper action |
| [in] | grasp_epsilon | The epsilon window of the grasp. |
| [in] | action_server | A pointer to a gripper action server |
| [in] | goal | A 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.
| [in] | gripper | A gripper instance to execute the command |
Definition at line 86 of file franka_gripper.cpp.
| bool franka_gripper::move | ( | const franka::Gripper & | gripper, |
| const MoveGoalConstPtr & | goal | ||
| ) |
Calls the libfranka move service of the gripper.
| [in] | gripper | A gripper instance to execute the command |
| [in] | goal | A move goal with target width and velocity |
Definition at line 82 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.
| [in] | gripper | A gripper instance to execute the command |
Definition at line 90 of file franka_gripper.cpp.
| bool franka_gripper::updateGripperState | ( | const franka::Gripper & | gripper, |
| franka::GripperState * | state | ||
| ) |
Reads a gripper state if possible.
| [in] | state | A gripper state to update |
| [in] | gripper | A pointer to a franka gripper |
Definition at line 20 of file franka_gripper.cpp.