1
1
#pragma once
2
2
3
- #include < cmath>
4
- #include < iostream>
5
3
#include < future>
6
4
7
5
#include < franka/exception.h>
@@ -16,85 +14,94 @@ struct GripperException : public std::runtime_error {
16
14
using std::runtime_error::runtime_error;
17
15
};
18
16
17
+ /* *
18
+ * @brief A wrapper around the franka::Gripper class that adds asynchronous functionality.
19
+ */
19
20
class Gripper : public franka ::Gripper {
20
21
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) {}
36
23
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)) {}
39
25
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.
45
38
*/
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 ;
47
41
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,
50
47
*/
51
- [[nodiscard]] bool isGrasping ( ) const ;
48
+ std::future< bool > moveAsync ( double width, double speed ) const ;
52
49
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.
58
54
*/
59
- bool move (double width );
55
+ bool open (double speed );
60
56
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.
66
62
*/
67
- bool moveUnsafe (double width );
63
+ std::future< bool > openAsync (double speed );
68
64
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.
74
68
*/
75
- std::future<bool > moveAsync ( double width );
69
+ std::future<bool > homingAsync ( );
76
70
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 ();
80
76
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
+ }
84
83
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
+ }
86
90
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
+ }
92
97
93
98
/* *
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
+
98
105
};
99
106
100
- } // namepace franky
107
+ } // namespace franky
0 commit comments