Skip to content

Commit 11506e6

Browse files
Reworked gripper API
1 parent 2b003e9 commit 11506e6

File tree

5 files changed

+108
-180
lines changed

5 files changed

+108
-180
lines changed

franky/__init__.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,3 @@
1-
from .gripper import Gripper
21
from .robot import Robot
32
from .robot_web_session import RobotWebSession
43
from .reaction import (
@@ -35,6 +34,7 @@
3534
LinearMotion,
3635
CartesianPoseStopMotion,
3736
JointPositionStopMotion,
37+
Gripper,
3838
Kinematics,
3939
RobotPose,
4040
RobotVelocity,

franky/gripper.py

-15
This file was deleted.

include/franky/gripper.hpp

+70-63
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,5 @@
11
#pragma once
22

3-
#include <cmath>
4-
#include <iostream>
53
#include <future>
64

75
#include <franka/exception.h>
@@ -16,85 +14,94 @@ struct GripperException : public std::runtime_error {
1614
using std::runtime_error::runtime_error;
1715
};
1816

17+
/**
18+
* @brief A wrapper around the franka::Gripper class that adds asynchronous functionality.
19+
*/
1920
class Gripper : public franka::Gripper {
2021
public:
21-
// Maximum speed of the gripper [m/s]
22-
static constexpr double max_speed{0.1};
23-
24-
/**
25-
* @param fci_hostname The hostname of the Franka robot.
26-
* @param speed The speed of the gripper. Default is 0.04.
27-
* @param force The force of the gripper. Default is 20.0.
28-
*/
29-
explicit Gripper(const std::string &fci_hostname, double speed = 0.04, double force = 20.0);
30-
31-
// Force of the gripper [N]
32-
double gripper_force{20.0};
33-
34-
// Speed of the gripper [m/s]
35-
double gripper_speed{0.04};
22+
explicit Gripper(const std::string &franka_address) : franka::Gripper(franka_address) {}
3623

37-
// Flag to indicate if the gripper has an error
38-
bool has_error{false};
24+
Gripper(Gripper &&gripper) noexcept: franka::Gripper(std::move(gripper)) {}
3925

40-
// Maximum width of the gripper [m]
41-
const double max_width{0.081 + width_calibration};
42-
43-
/*
44-
* @brief Get the current width of the gripper.
26+
/**
27+
* @brief Asynchronous variant of the franka::Gripper::grasp function.
28+
*
29+
* @param width Size of the object to grasp in [m].
30+
* @param speed Closing speed in [m/s].
31+
* @param force Grasping force in [N].
32+
* @param epsilon_inner Maximum tolerated deviation when the actual grasped width is smaller than the commanded grasp
33+
* width.
34+
* @param epsilon_outer Maximum tolerated deviation when the actual grasped width is larger than the commanded grasp
35+
* width.
36+
* @return Future that becomes ready when the grasp is finished. Contains true if an object has been grasped, false
37+
* otherwise.
4538
*/
46-
[[nodiscard]] double width() const;
39+
std::future<bool> graspAsync(
40+
double width, double speed, double force, double epsilon_inner = 0.005, double epsilon_outer = 0.005) const;
4741

48-
/*
49-
* @brief Check if the gripper is grasping.
42+
/**
43+
* @brief Asynchronous variant of the franka::Gripper::move function.
44+
* @param width Intended opening width in [m].
45+
* @param speed Speed of the movement in [m/s].
46+
* @return Future that becomes ready when the movement is finished. Contains true if the movement was successful,
5047
*/
51-
[[nodiscard]] bool isGrasping() const;
48+
std::future<bool> moveAsync(double width, double speed) const;
5249

53-
/*
54-
* @brief Move the gripper to the given width.
55-
*
56-
* @param width The width to move to [m]
57-
* @return True if the gripper moved successfully.
50+
/**
51+
* @brief Opens the gripper fully.
52+
* @param speed Speed of the movement in [m/s].
53+
* @return True if the gripper was opened successfully.
5854
*/
59-
bool move(double width);
55+
bool open(double speed);
6056

61-
/*
62-
* @brief Move the gripper to the given width without checking the current width.
63-
*
64-
* @param width The width to move to [m]
65-
* @return True if the gripper moved successfully.
57+
/**
58+
* @brief Asynchronous variant of the open function.
59+
* @param speed Speed of the movement in [m/s].
60+
* @return Future that becomes ready when the gripper is fully opened. Contains true if the gripper was opened
61+
* successfully.
6662
*/
67-
bool moveUnsafe(double width);
63+
std::future<bool> openAsync(double speed);
6864

69-
/*
70-
* @brief Move the gripper to the given width asynchronously.
71-
*
72-
* @param width The width to move to [m]
73-
* @return A future that will be set to true if the gripper moved successfully.
65+
/**
66+
* @brief Asynchronous variant of the franka::Gripper::homing function.
67+
* @return A future that becomes ready when the homing is finished. Contains true if the homing was successful.
7468
*/
75-
std::future<bool> moveAsync(double width);
69+
std::future<bool> homingAsync();
7670

77-
bool open();
78-
bool clamp();
79-
bool clamp(double min_clamping_width);
71+
/**
72+
* @brief Asynchronous variant of the franka::Gripper::stop function.
73+
* @return A future that becomes ready when the stop is finished. Contains true if the stop was successful.
74+
*/
75+
std::future<bool> stopAsync();
8076

81-
bool release();
82-
bool release(double width); // [m]
83-
bool releaseRelative(double width); // [m]
77+
/**
78+
* @brief Current opening width of the gripper [m]
79+
*/
80+
[[nodiscard]] inline double width() const {
81+
return state().width;
82+
}
8483

85-
::franka::GripperState get_state();
84+
/**
85+
* @brief Whether the gripper is grasping
86+
*/
87+
[[nodiscard]] inline bool is_grasped() const {
88+
return state().is_grasped;
89+
}
8690

87-
private:
88-
// Difference from gripper jaws [m
89-
const double width_calibration{0.004};
90-
// Minimum width of the gripper [m]
91-
const double min_width{0.002};
91+
/**
92+
* @brief Maximum width of the gripper [m]
93+
*/
94+
[[nodiscard]] inline double max_width() const {
95+
return state().max_width;
96+
}
9297

9398
/**
94-
* Save clamp width and compare it in the is_grasping method. If it's smaller,
95-
* the gripper moves and the object is missing. [m]
96-
*/
97-
double last_clamp_width{};
99+
* @brief Current gripper state.
100+
*/
101+
[[nodiscard]] inline franka::GripperState state() const {
102+
return readOnce();
103+
}
104+
98105
};
99106

100-
} // namepace franky
107+
} // namespace franky

python/python.cpp

+23-22
Original file line numberDiff line numberDiff line change
@@ -867,32 +867,33 @@ PYBIND11_MODULE(_franky, m) {
867867
std::shared_ptr<StopMotion<franka::JointPositions>>>(m, "JointPositionStopMotion")
868868
.def(py::init<>());
869869

870-
py::class_<Gripper>(m, "GripperInternal")
871-
.def(py::init<const std::string &, double, double>(), "fci_hostname"_a, "speed"_a = 0.02, "force"_a = 20.0)
872-
.def_readwrite("gripper_force", &Gripper::gripper_force)
873-
.def_readwrite("gripper_speed", &Gripper::gripper_speed)
874-
.def_readonly("max_width", &Gripper::max_width)
875-
.def_readonly("has_error", &Gripper::has_error)
876-
.def("homing", &Gripper::homing, py::call_guard<py::gil_scoped_release>())
870+
py::class_<Gripper>(m, "Gripper")
871+
.def(py::init<const std::string &>(), "fci_hostname"_a)
877872
.def("grasp", &Gripper::grasp,
878-
"width"_a, "speed"_a, "force"_a, "epsilon_inner"_a = 0.005, "epsilon_outer"_a = 0.005,
879-
py::call_guard<py::gil_scoped_release>())
880-
.def("move", &franka::Gripper::move, "width"_a, "speed"_a, py::call_guard<py::gil_scoped_release>())
873+
"width"_a,
874+
"speed"_a,
875+
"force"_a,
876+
"epsilon_inner"_a = 0.005,
877+
"epsilon_outer"_a = 0.005)
878+
.def("grasp_async", &Gripper::graspAsync,
879+
"width"_a,
880+
"speed"_a,
881+
"force"_a,
882+
"epsilon_inner"_a = 0.005,
883+
"epsilon_outer"_a = 0.005)
884+
.def("move", &Gripper::move, "width"_a, "speed"_a)
885+
.def("move_async", &Gripper::moveAsync, "width"_a, "speed"_a)
886+
.def("open", &Gripper::open, "speed"_a)
887+
.def("open_async", &Gripper::openAsync, "speed"_a)
888+
.def("homing", &Gripper::homing)
889+
.def("homing_async", &Gripper::homingAsync)
881890
.def("stop", &Gripper::stop)
882-
.def("move", &Gripper::move, "width"_a, py::call_guard<py::gil_scoped_release>())
883-
.def("move_unsafe", &Gripper::move, "width"_a, py::call_guard<py::gil_scoped_release>())
884-
.def("open", &Gripper::open, py::call_guard<py::gil_scoped_release>())
885-
.def("clamp", py::overload_cast<>(&Gripper::clamp), py::call_guard<py::gil_scoped_release>())
886-
.def("clamp", py::overload_cast<double>(&Gripper::clamp),
887-
"min_clamping_width"_a, py::call_guard<py::gil_scoped_release>())
888-
.def("release", py::overload_cast<>(&Gripper::release), py::call_guard<py::gil_scoped_release>())
889-
.def("release", py::overload_cast<double>(&Gripper::release),
890-
"width"_a, py::call_guard<py::gil_scoped_release>())
891-
.def("release_relative", &Gripper::releaseRelative, "width_relative"_a, py::call_guard<py::gil_scoped_release>())
892-
.def_property_readonly("state", &Gripper::get_state)
891+
.def("stop_async", &Gripper::stopAsync)
892+
.def_property_readonly("state", &Gripper::state)
893893
.def_property_readonly("server_version", (uint16_t (Gripper::*)()) &Gripper::serverVersion)
894894
.def_property_readonly("width", &Gripper::width)
895-
.def_property_readonly("is_grasping", &Gripper::isGrasping);
895+
.def_property_readonly("is_grasped", &Gripper::is_grasped)
896+
.def_property_readonly("max_width", &Gripper::max_width);
896897

897898
py::class_<Kinematics>(m, "Kinematics")
898899
.def_static("forward", &Kinematics::forward, "q"_a)

src/gripper.cpp

+14-79
Original file line numberDiff line numberDiff line change
@@ -2,94 +2,29 @@
22

33
namespace franky {
44

5-
Gripper::Gripper(const std::string &fci_hostname, double speed, double force)
6-
: franka::Gripper(fci_hostname), gripper_speed(speed), gripper_force(force) {}
7-
8-
double Gripper::width() const {
9-
auto state = readOnce();
10-
return state.width + width_calibration;
11-
}
12-
13-
bool Gripper::isGrasping() const {
14-
const double current_width = width();
15-
const bool libfranka_is_grasped = readOnce().is_grasped;
16-
const bool width_is_grasped = std::abs(current_width - last_clamp_width) < 0.003; // [m], magic number
17-
const bool width_larger_than_threshold = current_width > 0.005; // [m]
18-
return libfranka_is_grasped && width_is_grasped && width_larger_than_threshold;
19-
}
20-
21-
bool Gripper::move(double width) { // [m]
22-
try {
23-
const bool result = ((franka::Gripper *) this)->move(width - width_calibration, gripper_speed); // [m] [m/s]
24-
const double current_width = this->width();
25-
if (current_width > 0.01 && std::abs(current_width - width) > 0.01) {
26-
has_error = true;
27-
throw GripperException(
28-
"Gripper does (" + std::to_string(current_width) + ") not do what it should (" + std::to_string(width) +
29-
").");
30-
return false;
31-
}
32-
if (result) {
33-
has_error = false;
34-
}
35-
return result;
36-
} catch (franka::Exception const &e) {
37-
has_error = true;
38-
std::cout << e.what() << std::endl;
39-
this->stop();
40-
this->homing();
41-
return ((franka::Gripper *) this)->move(width - width_calibration, gripper_speed); // [m] [m/s]
42-
}
43-
}
44-
45-
bool Gripper::moveUnsafe(double width) { // [m]
46-
const bool result_stop = ((franka::Gripper *) this)->stop();
47-
return ((franka::Gripper *) this)->move(width - width_calibration, gripper_speed); // [m] [m/s]
48-
}
49-
50-
std::future<bool> Gripper::moveAsync(double width) { // [m]
51-
return std::async(std::launch::async, &Gripper::move, this, width - width_calibration);
52-
}
53-
54-
bool Gripper::open() {
55-
return move(max_width);
56-
}
57-
58-
bool Gripper::clamp() {
59-
const bool success = grasp(min_width, gripper_speed, gripper_force, min_width, 1.0); // [m] [m/s] [N] [m] [m]
60-
last_clamp_width = width();
61-
return success;
5+
std::future<bool> Gripper::graspAsync(
6+
double width, double speed, double force, double epsilon_inner, double epsilon_outer) const {
7+
return std::async(std::launch::async, &Gripper::grasp, this, width, speed, force, epsilon_inner, epsilon_outer);
628
}
639

64-
bool Gripper::clamp(double min_clamping_width) {
65-
const bool success = this->grasp(min_clamping_width, gripper_speed, gripper_force, min_width,
66-
1.0); // [m] [m/s] [N] [m] [m]
67-
last_clamp_width = this->width();
68-
return success;
10+
std::future<bool> Gripper::moveAsync(double width, double speed) const {
11+
return std::async(std::launch::async, &Gripper::move, this, width, speed);
6912
}
7013

71-
bool Gripper::release() { // [m]
72-
return release(last_clamp_width);
14+
bool Gripper::open(double speed) {
15+
return move(max_width(), speed);
7316
}
7417

75-
bool Gripper::release(double width) { // [m]
76-
try {
77-
// stop();
78-
return move(width);
79-
} catch (franka::Exception const &e) {
80-
std::cout << e.what() << std::endl;
81-
homing();
82-
stop();
83-
return move(width);
84-
}
18+
std::future<bool> Gripper::openAsync(double speed) {
19+
return std::async(std::launch::async, &Gripper::open, this, speed);
8520
}
8621

87-
bool Gripper::releaseRelative(double width_relative) { // [m]
88-
return release(width() + width_relative);
22+
std::future<bool> Gripper::homingAsync() {
23+
return std::async(std::launch::async, &Gripper::homing, this);
8924
}
9025

91-
::franka::GripperState Gripper::get_state() {
92-
return readOnce();
26+
std::future<bool> Gripper::stopAsync() {
27+
return std::async(std::launch::async, &Gripper::stop, this);
9328
}
9429

95-
} // namepace franky
30+
} // namespace franky

0 commit comments

Comments
 (0)