66
77#include " protocol_logic.hpp"
88
9-
10- namespace robotiq_hande_driver
11- {
9+ namespace robotiq_hande_driver {
1210
1311constexpr auto GRIPPER_CURRENT_SCALE = 0.01 ;
1412constexpr auto MAX_SPEED = 255 ;
@@ -18,8 +16,7 @@ constexpr auto MAX_FORCE = 255;
1816 * @brief This class contains high-level gripper commands and status.
1917 */
2018class GripperApplication {
21- public:
22-
19+ public:
2320 struct Status {
2421 bool is_reset;
2522 bool is_ready;
@@ -50,9 +47,18 @@ class GripperApplication {
5047 * @param stop_bit Modbus serial stopbit.
5148 * @param slave_id Modbus slave id.
5249 * @return None.
53- * @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
50+ * @note The status should be checked to verify successful execution. An exception is thrown if
51+ * communication issues occur.
5452 */
55- void initialize (double gripper_position_min, double gripper_position_max, std::string& tty_port, int baudrate, char parity, int data_bits, int stop_bit, int slave_id) {
53+ void initialize (
54+ double gripper_position_min,
55+ double gripper_position_max,
56+ std::string& tty_port,
57+ int baudrate,
58+ char parity,
59+ int data_bits,
60+ int stop_bit,
61+ int slave_id) {
5662 gripper_position_min_ = gripper_position_min;
5763 gripper_position_max_ = gripper_position_max;
5864 gripper_postion_step_ = (gripper_position_max_ - gripper_position_min_) / 255.0 ;
@@ -62,7 +68,8 @@ class GripperApplication {
6268 /* *
6369 * @brief Configures driver session.
6470 * @return int, when error <0.
65- * @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
71+ * @note The status should be checked to verify successful execution. An exception is thrown if
72+ * communication issues occur.
6673 */
6774 int configure () {
6875 int result;
@@ -77,7 +84,8 @@ class GripperApplication {
7784 *
7885 * @param none
7986 * @return None.
80- * @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
87+ * @note The status should be checked to verify successful execution. An exception is thrown if
88+ * communication issues occur.
8189 */
8290 void cleanup () {
8391 protocol_logic_.cleanup ();
@@ -88,7 +96,8 @@ class GripperApplication {
8896 *
8997 * @param none
9098 * @return None.
91- * @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
99+ * @note The status should be checked to verify successful execution. An exception is thrown if
100+ * communication issues occur.
92101 */
93102 void stop () {
94103 protocol_logic_.stop ();
@@ -99,7 +108,8 @@ class GripperApplication {
99108 *
100109 * @param none
101110 * @return None.
102- * @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
111+ * @note The status should be checked to verify successful execution. An exception is thrown if
112+ * communication issues occur.
103113 */
104114 void reset () {
105115 protocol_logic_.reset ();
@@ -110,7 +120,8 @@ class GripperApplication {
110120 *
111121 * @param none
112122 * @return None.
113- * @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
123+ * @note The status should be checked to verify successful execution. An exception is thrown if
124+ * communication issues occur.
114125 */
115126 void auto_release () {
116127 protocol_logic_.auto_release ();
@@ -121,13 +132,14 @@ class GripperApplication {
121132 *
122133 * @param blocking If true wait until the gripper is active.
123134 * @return None.
124- * @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
135+ * @note The status should be checked to verify successful execution. An exception is thrown if
136+ * communication issues occur.
125137 */
126- void activate (bool blocking= true ) {
138+ void activate (bool blocking = true ) {
127139 int iter = 0 ;
128140 read ();
129141
130- if (status_.is_ready )
142+ if (status_.is_ready )
131143 printf (" Gripper already active\n " );
132144 else {
133145 printf (" Activation in progress\n " );
@@ -147,18 +159,20 @@ class GripperApplication {
147159 *
148160 * @param none
149161 * @return None.
150- * @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
162+ * @note The status should be checked to verify successful execution. An exception is thrown if
163+ * communication issues occur.
151164 */
152165 void deactivate () {
153166 protocol_logic_.reset ();
154167 };
155168
156- /* *
169+ /* *
157170 * @brief Deactivates the gripper.
158171 *
159172 * @param none
160173 * @return None.
161- * @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
174+ * @note The status should be checked to verify successful execution. An exception is thrown if
175+ * communication issues occur.
162176 */
163177 void shutdown () {
164178 deactivate ();
@@ -170,7 +184,8 @@ class GripperApplication {
170184 *
171185 * @param none
172186 * @return None.
173- * @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
187+ * @note The status should be checked to verify successful execution. An exception is thrown if
188+ * communication issues occur.
174189 */
175190 void open () {
176191 set_position (gripper_position_max_);
@@ -181,7 +196,8 @@ class GripperApplication {
181196 *
182197 * @param none
183198 * @return None.
184- * @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
199+ * @note The status should be checked to verify successful execution. An exception is thrown if
200+ * communication issues occur.
185201 */
186202 void close () {
187203 set_position (gripper_position_min_);
@@ -192,7 +208,8 @@ class GripperApplication {
192208 *
193209 * @param none
194210 * @return The current gripper status.
195- * @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
211+ * @note The status should be checked to verify successful execution. An exception is thrown if
212+ * communication issues occur.
196213 */
197214 Status get_status () {
198215 return status_;
@@ -203,7 +220,8 @@ class GripperApplication {
203220 *
204221 * @param none
205222 * @return The current gripper fault status.
206- * @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
223+ * @note The status should be checked to verify successful execution. An exception is thrown if
224+ * communication issues occur.
207225 */
208226 FaultStatus get_fault_status () {
209227 return fault_status_;
@@ -214,18 +232,20 @@ class GripperApplication {
214232 *
215233 * @param none
216234 * @return The requested gripper position in meters.
217- * @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
235+ * @note The status should be checked to verify successful execution. An exception is thrown if
236+ * communication issues occur.
218237 */
219238 double get_requested_position () {
220- return requested_position_;
239+ return requested_position_;
221240 };
222241
223242 /* *
224243 * @brief Retrieves the actual position of the gripper.
225244 *
226245 * @param none
227246 * @return The actual gripper position in meters.
228- * @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
247+ * @note The status should be checked to verify successful execution. An exception is thrown if
248+ * communication issues occur.
229249 */
230250 double get_position () {
231251 return position_;
@@ -236,20 +256,24 @@ class GripperApplication {
236256 *
237257 * @param position The target position in meters.
238258 * @return None.
239- * @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
259+ * @note The status should be checked to verify successful execution. An exception is thrown if
260+ * communication issues occur.
240261 */
241- void set_position (double position, double force= 1.0 ) {
262+ void set_position (double position, double force = 1.0 ) {
242263 uint8_t scaled_force = static_cast <uint8_t >(force * MAX_FORCE);
243264 protocol_logic_.go_to (
244- (uint8_t )((gripper_position_max_ - position) / gripper_postion_step_), MAX_SPEED, scaled_force);
265+ (uint8_t )((gripper_position_max_ - position) / gripper_postion_step_),
266+ MAX_SPEED,
267+ scaled_force);
245268 };
246269
247270 /* *
248271 * @brief Retrieves the electric current drawn by the gripper.
249272 *
250273 * @param none
251274 * @return The electric current in amperes (range: 0–2.55 A)
252- * @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
275+ * @note The status should be checked to verify successful execution. An exception is thrown if
276+ * communication issues occur.
253277 */
254278 double get_current () {
255279 return current_;
@@ -260,7 +284,8 @@ class GripperApplication {
260284 *
261285 * @param none
262286 * @return None.
263- * @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
287+ * @note The status should be checked to verify successful execution. An exception is thrown if
288+ * communication issues occur.
264289 */
265290 void read ();
266291
@@ -269,13 +294,14 @@ class GripperApplication {
269294 *
270295 * @param none
271296 * @return None.
272- * @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
297+ * @note The status should be checked to verify successful execution. An exception is thrown if
298+ * communication issues occur.
273299 */
274300 void write () {
275301 protocol_logic_.refresh_registers ();
276302 };
277303
278- private:
304+ private:
279305 /* *
280306 * Handles protocol logic for mid-level abstraction.
281307 */
@@ -309,7 +335,6 @@ class GripperApplication {
309335 double gripper_position_min_;
310336 double gripper_position_max_;
311337 double gripper_postion_step_;
312-
313338};
314- } // namespace robotiq_hande_driver
339+ } // namespace robotiq_hande_driver
315340#endif // ROBOTIQ_HANDE_DRIVER__APPLICATION_HPP_
0 commit comments