13 #include <franka_gripper/GraspAction.h> 14 #include <franka_gripper/HomingAction.h> 15 #include <franka_gripper/MoveAction.h> 16 #include <franka_gripper/StopAction.h> 24 ROS_ERROR_STREAM(
"GripperServer: Exception reading gripper state: " << ex.what());
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;
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);
47 constexpr
double kSamePositionThreshold = 1e-4;
48 if (std::abs(target_width - state.
width) < kSamePositionThreshold) {
51 if (target_width >= state.
width) {
52 return gripper.
move(target_width, default_speed);
54 return gripper.
grasp(target_width, default_speed, goal->command.max_effort, grasp_epsilon.inner,
59 if (gripper_command_handler()) {
62 control_msgs::GripperCommandResult result;
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);
78 return gripper.
move(goal->width, goal->speed);
86 return gripper.
stop();
90 return gripper.
grasp(goal->width, goal->speed, goal->force, goal->epsilon.inner,
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 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(""))
#define ROS_ERROR_STREAM(args)
bool grasp(const franka::Gripper &gripper, const GraspGoalConstPtr &goal)
Calls the libfranka grasp service of the gripper.