franka_gripper.cpp
Go to the documentation of this file.
1 // Copyright (c) 2017 Franka Emika GmbH
2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
4 
5 #include <cmath>
6 #include <functional>
7 #include <thread>
8 
9 #include <ros/node_handle.h>
10 
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>
17 
18 namespace franka_gripper {
19 
21  try {
22  *state = gripper.readOnce();
23  } catch (const franka::Exception& ex) {
24  ROS_ERROR_STREAM("GripperServer: Exception reading gripper state: " << ex.what());
25  return false;
26  }
27  return true;
28 }
29 
31  const franka::Gripper& gripper,
32  const GraspEpsilon& grasp_epsilon,
33  double default_speed,
35  const control_msgs::GripperCommandGoalConstPtr& goal) {
36  auto gripper_command_handler = [goal, grasp_epsilon, default_speed, &gripper]() {
37  // HACK: As one gripper finger is <mimic>, MoveIt!'s trajectory execution manager
38  // only sends us the width of one finger. Multiply by 2 to get the intended width.
39  double target_width = 2 * goal->command.position;
40 
41  franka::GripperState state = gripper.readOnce();
42  if (target_width > state.max_width || target_width < 0.0) {
43  ROS_ERROR_STREAM("GripperServer: Commanding out of range width! max_width = "
44  << state.max_width << " command = " << target_width);
45  return false;
46  }
47  constexpr double kSamePositionThreshold = 1e-4;
48  if (std::abs(target_width - state.width) < kSamePositionThreshold) {
49  return true;
50  }
51  if (target_width >= state.width) {
52  return gripper.move(target_width, default_speed);
53  }
54  return gripper.grasp(target_width, default_speed, goal->command.max_effort, grasp_epsilon.inner,
55  grasp_epsilon.outer);
56  };
57 
58  try {
59  if (gripper_command_handler()) {
61  if (updateGripperState(gripper, &state)) {
62  control_msgs::GripperCommandResult result;
63  result.effort = 0.0;
64  result.position = state.width;
65  result.reached_goal = static_cast<decltype(result.reached_goal)>(true);
66  result.stalled = static_cast<decltype(result.stalled)>(false);
67  action_server->setSucceeded(result);
68  return;
69  }
70  }
71  } catch (const franka::Exception& ex) {
72  ROS_ERROR_STREAM("" << ex.what());
73  }
74  action_server->setAborted();
75 }
76 
77 bool move(const franka::Gripper& gripper, const MoveGoalConstPtr& goal) {
78  return gripper.move(goal->width, goal->speed);
79 }
80 
81 bool homing(const franka::Gripper& gripper, const HomingGoalConstPtr& /*goal*/) {
82  return gripper.homing();
83 }
84 
85 bool stop(const franka::Gripper& gripper, const StopGoalConstPtr& /*goal*/) {
86  return gripper.stop();
87 }
88 
89 bool grasp(const franka::Gripper& gripper, const GraspGoalConstPtr& goal) {
90  return gripper.grasp(goal->width, goal->speed, goal->force, goal->epsilon.inner,
91  goal->epsilon.outer);
92 }
93 
94 } // namespace franka_gripper
bool move(const franka::Gripper &gripper, const MoveGoalConstPtr &goal)
Calls the libfranka move service of the gripper.
bool grasp(double width, double speed, double force, double epsilon_inner=0.005, double epsilon_outer=0.005) const
bool stop() const
bool stop(const franka::Gripper &gripper, const StopGoalConstPtr &)
Calls the libfranka stop service of the gripper to stop applying force.
bool homing(const franka::Gripper &gripper, const HomingGoalConstPtr &)
Calls the libfranka homing service of the gripper.
GripperState readOnce() const
bool move(double width, double speed) const
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
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.
bool updateGripperState(const franka::Gripper &gripper, franka::GripperState *state)
Reads a gripper state if possible.
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
bool homing() const
#define ROS_ERROR_STREAM(args)
bool grasp(const franka::Gripper &gripper, const GraspGoalConstPtr &goal)
Calls the libfranka grasp service of the gripper.


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