10 using control_msgs::GripperCommandAction;
11 using franka_gripper::GraspAction;
12 using franka_gripper::HomingAction;
13 using franka_gripper::MoveAction;
14 using franka_gripper::StopAction;
22 "Could not find required parameter '" << ns <<
"/arm_id'");
25 std::string finger1 =
arm_id +
"_finger_joint1";
26 std::string finger2 =
arm_id +
"_finger_joint2";
55 this->
action_stop_ = std::make_unique<SimpleActionServer<StopAction>>(
59 this->
action_homing_ = std::make_unique<SimpleActionServer<HomingAction>>(
67 this->
action_move_ = std::make_unique<SimpleActionServer<MoveAction>>(
75 this->
action_grasp_ = std::make_unique<SimpleActionServer<GraspAction>>(
83 this->
action_gc_ = std::make_unique<SimpleActionServer<GripperCommandAction>>(
85 this->
action_gc_->registerPreemptCallback([&]() {
92 "Successfully initialized Franka Gripper Controller for joints '"
93 << finger1 <<
"' and '" << finger2 <<
"'");
120 if (state == State::IDLE) {
135 if (state == State::HOLDING) {
140 std::lock_guard<std::mutex> lock(this->
mutex_);
147 if (w_d - tolerance.inner < width and width < w_d + tolerance.outer) {
149 if (state == State::MOVING) {
159 if (state == State::GRASPING or state == State::MOVING) {
163 static int speed_threshold_counter = 0;
166 speed_threshold_counter++;
168 speed_threshold_counter = 0;
172 if (state == State::GRASPING) {
185 speed_threshold_counter = 0;
202 std::lock_guard<std::mutex> lock(this->
mutex_);
207 std::lock_guard<std::mutex> lock(this->
mutex_);
212 std::lock_guard<std::mutex> lock(this->
mutex_);
218 if (except != State::MOVING and this->
action_move_ !=
nullptr and
220 franka_gripper::MoveResult
result;
221 result.success =
static_cast<decltype(
result.success)
>(
false);
225 if (except != State::GRASPING and this->
action_grasp_ !=
nullptr and
227 franka_gripper::GraspResult
result;
228 result.success =
static_cast<decltype(
result.success)
>(
false);
232 if (except != State::MOVING and this->
action_homing_ !=
nullptr and
234 franka_gripper::HomingResult
result;
235 result.success =
static_cast<decltype(
result.success)
>(
false);
247 std::lock_guard<std::mutex> lock(this->
mutex_);
248 if (this->
state_ != original) {
259 interrupt(
"Command interrupted, because stop action was called", State::IDLE);
266 franka_gripper::StopResult
result;
267 result.success =
static_cast<decltype(
result.success)
>(
true);
274 if (this->
state_ != State::IDLE) {
275 this->
interrupt(
"Command interrupted, because new homing action called", State::MOVING);
278 franka_gripper::GraspEpsilon eps;
293 .speed_desired = 0.02,
304 franka_gripper::HomingResult
result;
305 if (this->
state_ != State::IDLE) {
306 result.success =
static_cast<decltype(
result.success)
>(
false);
307 result.error =
"Unexpected state transistion: The gripper not in IDLE as expected";
312 result.success =
static_cast<decltype(
result.success)
>(
true);
318 "New Move Action Goal received: " <<
goal->width <<
" m");
319 if (
goal->speed < 0) {
320 franka_gripper::MoveResult
result;
321 result.success =
static_cast<decltype(
result.success)
>(
false);
322 result.error =
"Only positive speeds allowed";
328 franka_gripper::MoveResult
result;
329 result.success =
static_cast<decltype(
result.success)
>(
false);
335 if (this->
state_ != State::IDLE) {
336 interrupt(
"Command interrupted, because new move action called", State::MOVING);
347 franka_gripper::MoveResult
result;
348 if (not move_succeeded) {
349 result.success =
static_cast<decltype(
result.success)
>(
false);
350 result.error =
"Unexpected state transistion: The gripper not in IDLE as expected";
354 franka_gripper::GraspEpsilon eps;
359 bool ok =
goal->width - eps.inner < width and width <
goal->width + eps.outer;
366 "New Grasp Action Goal received: " <<
goal->force <<
"N");
369 franka_gripper::GraspResult
result;
370 result.success =
static_cast<decltype(
result.success)
>(
false);
372 "Can only grasp inside finger width from [0 .. " + std::to_string(
kMaxFingerWidth) +
"[";
376 if (
goal->speed < 0) {
377 franka_gripper::GraspResult
result;
378 result.success =
static_cast<decltype(
result.success)
>(
false);
379 result.error =
"Only positive speeds allowed";
384 if (this->
state_ != State::IDLE) {
385 interrupt(
"Command interrupted, because new grasp action called", State::GRASPING);
396 franka_gripper::GraspResult
result;
397 if (this->
state_ != State::HOLDING) {
398 result.success =
static_cast<decltype(
result.success)
>(
false);
399 result.error =
"Unexpected state transistion: The gripper not in HOLDING as expected";
404 result.success =
static_cast<decltype(
result.success)
>(grasp_succeeded);
405 if (not grasp_succeeded) {
408 "When the gripper stopped (below speed of " + std::to_string(this->
speed_threshold_) +
409 " m/s the width between the fingers was not at " + std::to_string(
goal->width) +
"m (-" +
410 std::to_string(
goal->epsilon.inner) +
"m/+" + std::to_string(
goal->epsilon.outer) +
411 "m) but at " + std::to_string(current_width) +
"m";
419 control_msgs::GripperCommandResult
result;
422 double width_d =
goal->command.position * 2.0;
425 <<
goal->command.position <<
"m, "
426 <<
goal->command.max_effort <<
"N");
430 "Commanding out of range position! max_position = " + std::to_string(
kMaxFingerWidth / 2) +
431 ", commanded position = " + std::to_string(
goal->command.position) +
432 ". Be aware that you command the position of"
433 " each finger which is half of the total opening width!";
435 result.reached_goal =
static_cast<decltype(
result.reached_goal)
>(
false);
440 franka_gripper::GraspEpsilon eps;
445 constexpr
double kMinimumGraspForce = 1e-4;
446 bool succeeded =
false;
448 if (std::abs(
goal->command.max_effort) < kMinimumGraspForce or width_d > current_width) {
462 if (this->
state_ != State::HOLDING) {
463 result.reached_goal =
static_cast<decltype(
result.reached_goal)
>(
false);
464 std::string
error =
"Unexpected state transition: The gripper not in HOLDING as expected";
472 result.stalled =
static_cast<decltype(
result.stalled)
>(
false);
473 result.reached_goal =
static_cast<decltype(
result.reached_goal)
>(succeeded);
481 franka_gripper::GraspEpsilon eps;
486 Config{.
width_desired = width, .speed_desired = speed, .force_desired = 0, .tolerance = eps});
489 return this->
state_ == State::IDLE;
495 const franka_gripper::GraspEpsilon& epsilon) {
497 double direction = std::copysign(1.0, width - current_width);
499 .speed_desired = speed,
500 .force_desired = direction * force,
505 return width -
epsilon.inner < current_width and current_width < width +
epsilon.outer;