11 #include <franka/exception.h>
12 #include <franka/gripper_state.h>
13 #include <franka_gripper/GraspAction.h>
14 #include <franka_gripper/HomingAction.h>
15 #include <franka_gripper/MoveAction.h>
16 #include <franka_gripper/StopAction.h>
22 *state = gripper.readOnce();
23 }
catch (
const franka::Exception& ex) {
24 ROS_ERROR_STREAM(
"GripperServer: Exception reading gripper state: " << ex.what());
31 const franka::Gripper& gripper,
32 const GraspEpsilon& grasp_epsilon,
35 const control_msgs::GripperCommandGoalConstPtr& goal) {
36 auto gripper_command_handler = [goal, grasp_epsilon, default_speed, &gripper]() {
39 double target_width = 2 * goal->command.position;
41 franka::GripperState state = gripper.readOnce();
42 if (target_width > state.max_width || target_width < 0.0) {
43 std::string error =
"Commanding out of range position! max_position = " +
44 std::to_string(state.max_width / 2) +
45 ", commanded position = " + std::to_string(goal->command.position) +
46 ". Be aware that you command the position of"
47 " each finger which is half of the total opening width!";
51 constexpr
double kSamePositionThreshold = 1e-4;
52 if (std::abs(target_width - state.width) < kSamePositionThreshold) {
55 constexpr
double kMinimumGraspForce = 1e-4;
56 if (std::abs(goal->command.max_effort) < kMinimumGraspForce or target_width >= state.width) {
57 return gripper.move(target_width, default_speed);
59 return gripper.grasp(target_width, default_speed, goal->command.max_effort, grasp_epsilon.inner,
64 if (gripper_command_handler()) {
65 franka::GripperState state;
67 control_msgs::GripperCommandResult result;
69 result.position = state.width;
70 result.reached_goal =
static_cast<decltype(result.reached_goal)
>(
true);
71 result.stalled =
static_cast<decltype(result.stalled)
>(
false);
76 }
catch (
const franka::Exception& ex) {
82 bool move(
const franka::Gripper& gripper,
const MoveGoalConstPtr& goal) {
83 return gripper.move(goal->width, goal->speed);
86 bool homing(
const franka::Gripper& gripper,
const HomingGoalConstPtr& ) {
87 return gripper.homing();
90 bool stop(
const franka::Gripper& gripper,
const StopGoalConstPtr& ) {
91 return gripper.stop();
94 bool grasp(
const franka::Gripper& gripper,
const GraspGoalConstPtr& goal) {
95 return gripper.grasp(goal->width, goal->speed, goal->force, goal->epsilon.inner,