Skip to content

Commit 4c45f9e

Browse files
committed
CHG: comments
1 parent 66ce2c8 commit 4c45f9e

File tree

4 files changed

+137
-122
lines changed

4 files changed

+137
-122
lines changed

robotiq_hande_driver/include/application.hpp

Lines changed: 59 additions & 45 deletions
Original file line numberDiff line numberDiff line change
@@ -17,12 +17,12 @@ constexpr auto MAX_SPEED = 255;
1717
constexpr auto MAX_FORCE = 255;
1818

1919
/**
20-
* @brief This class contains high level gripper commands and status
20+
* @brief This class contains high-level gripper commands and status.
2121
*/
22-
class ApplicationLayer{
22+
class ApplicationLayer {
2323
public:
2424

25-
struct Status{
25+
struct Status {
2626
bool is_reset;
2727
bool is_ready;
2828
bool is_moving;
@@ -32,7 +32,7 @@ class ApplicationLayer{
3232
bool object_detected;
3333
};
3434

35-
struct FaultStatus{
35+
struct FaultStatus {
3636
bool is_error;
3737
};
3838

@@ -41,22 +41,22 @@ class ApplicationLayer{
4141
~ApplicationLayer() {};
4242

4343
/**
44-
* @brief Stops movement of the gripper
44+
* @brief Stops the gripper movement.
4545
*
4646
* @param none
47-
* @return none
47+
* @return None.
4848
* @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
4949
*/
5050
void stop() {
5151
protocol_logic_.stop();
5252
};
5353

5454
/**
55-
* @brief Resets the gripper: deactivate and activate again
55+
* @brief Resets the gripper by deactivating and reactivating it.
5656
*
5757
* @param none
58-
* @return none
59-
* @note see status on success, exception thrown if communicatoin issues
58+
* @return None.
59+
* @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
6060
*/
6161
void reset() {
6262
protocol_logic_.reset();
@@ -66,147 +66,161 @@ class ApplicationLayer{
6666
* Emergency auto-release, gripper fingers are slowly opened, reactivation necessary
6767
*
6868
* @param none
69-
* @return none
70-
* @note see status on success, exception thrown if communicatoin issues
69+
* @return None.
70+
* @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
7171
*/
7272
void auto_release() {
7373
protocol_logic_.auto_release();
7474
};
7575

7676
/**
77-
* @brief Activates the gripper, after that it can be used
77+
* @brief Activates the gripper, making it ready for use.
7878
*
7979
* @param none
80-
* @return none
81-
* @note see status on success, exception thrown if communicatoin issues
80+
* @return None.
81+
* @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
8282
*/
8383
void activate() {
8484
protocol_logic_.activate();
8585
};
8686

8787
/**
88-
* @brief Opens the gripper
88+
* @brief Opens the gripper.
8989
*
9090
* @param none
91-
* @return none
92-
* @note see status on success, exception thrown if communicatoin issues
91+
* @return None.
92+
* @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
9393
*/
9494
void open() {
9595
set_position(GRIPPER_POSITION_MAX);
9696
};
9797

9898
/**
99-
* @brief Closes the gripper
99+
* @brief Closes the gripper.
100100
*
101101
* @param none
102-
* @return none
103-
* @note see status on success, exception thrown if communicatoin issues
102+
* @return None.
103+
* @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
104104
*/
105105
void close() {
106106
set_position(GRIPPER_POSITION_MIN);
107107
};
108108

109109
/**
110-
* @brief Returns the gripper status
110+
* @brief Retrieves the gripper status.
111111
*
112112
* @param none
113-
* @return Gripper status
114-
* @note see status on success, exception thrown if communicatoin issues
113+
* @return The current gripper status.
114+
* @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
115115
*/
116116
Status get_status() {
117117
return status_;
118118
};
119119

120120
/**
121-
* @brief Returns the gripper fault status
121+
* @brief Retrieves the gripper fault status.
122122
*
123123
* @param none
124-
* @return Fault Status
125-
* @note see status on success, exception thrown if communicatoin issues
124+
* @return The current gripper fault status.
125+
* @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
126126
*/
127127
FaultStatus get_fault_status() {
128128
return fault_status_;
129129
};
130130

131131
/**
132-
* @brief Returns the gripper requested position
132+
* @brief Retrieves the requested position of the gripper.
133133
*
134134
* @param none
135-
* @return Gripper requested position
136-
* @note see status on success, exception thrown if communicatoin issues
135+
* @return The requested gripper position in meters.
136+
* @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
137137
*/
138138
double get_requested_position() {
139139
return requested_position_;
140140
};
141141

142142
/**
143-
* @brief Returns the gripper position
143+
* @brief Retrieves the actual position of the gripper.
144144
*
145145
* @param none
146-
* @return Gripper position in [m]
147-
* @note see status on success, exception thrown if communicatoin issues
146+
* @return The actual gripper position in meters.
147+
* @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
148148
*/
149149
double get_position() {
150150
return position_;
151151
};
152152

153153
/**
154-
* @brief Moves the gripper to requested position
154+
* @brief Moves the gripper to the requested position.
155155
*
156-
* @param position to which the gripper has to move, in [m]
157-
* @return none
158-
* @note see status on success, exception thrown if communicatoin issues
156+
* @param position The target position in meters.
157+
* @return None.
158+
* @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
159159
*/
160160
void set_position(double position) {
161161
protocol_logic_.go_to(
162162
(uint8_t)((GRIPPER_POSITION_MAX - position) / GRIPPER_POSITION_STEP), MAX_SPEED, MAX_FORCE);
163163
};
164164

165165
/**
166-
* @brief Returns the gripper current
166+
* @brief Retrieves the electric current drawn by the gripper.
167167
*
168168
* @param none
169-
* @return Gripper current in [A] (range: 0-2.55A)
170-
* @note see status on success, exception thrown if communicatoin issues
169+
* @return The electric current in amperes (range: 0–2.55 A)
170+
* @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
171171
*/
172172
double get_current() {
173173
return current_;
174174
};
175175

176+
/**
177+
* @brief Closes the gripper.
178+
*
179+
* @param none
180+
* @return None.
181+
* @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
182+
*/
176183
void read();
177184

185+
/**
186+
* @brief Closes the gripper.
187+
*
188+
* @param none
189+
* @return None.
190+
* @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
191+
*/
178192
void write() {
179193
protocol_logic_.refresh_registers();
180194
};
181195

182196
private:
183197
/**
184-
* Protocol logic, used for middle level abstraction
198+
* Handles protocol logic for mid-level abstraction.
185199
*/
186200
ProtocolLogic protocol_logic_;
187201

188202
/**
189-
* Struct with status bits
203+
* Stores the gripper status bits.
190204
*/
191205
Status status_;
192206

193207
/**
194-
* Struct with fault status bits
208+
* Stores the fault status bits.
195209
*/
196210
FaultStatus fault_status_;
197211

198212
/**
199-
* Requested position of the gripper, in [m]
213+
* Stores the requested position of the gripper in meters.
200214
*/
201215
double requested_position_;
202216

203217
/**
204-
* POsition of the gripper, in [m]
218+
* Stores the actual position of the gripper in meters.
205219
*/
206220
double position_;
207221

208222
/**
209-
* Current flowin through the gripper, in [A]
223+
* Stores the electric current drawn by the gripper in amperes.
210224
*/
211225
double current_;
212226

robotiq_hande_driver/include/communication.hpp

Lines changed: 27 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -54,31 +54,31 @@ class Communication{
5454
};
5555

5656
/**
57-
* @brief Connect to gripper using modbus rtu and virtual socket
57+
* @brief Connects to the gripper using Modbus RTU and a virtual socket.
5858
*
5959
* @param none
60-
* @return none
61-
* @note see status on success, exception thrown in case of communication issues
60+
* @return None.
61+
* @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
6262
*/
6363
void connect();
6464

6565
/**
66-
* @brief Disconnect from gripper using modbus rtu and virtual socket
66+
* @brief Disconnects from the gripper using Modbus RTU and a virtual socket.
6767
*
6868
* @param none
69-
* @return none
70-
* @note see status on success, exception thrown in case of communication issues
69+
* @return None.
70+
* @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
7171
*/
7272
void disconnect() {
7373
modbus_close(mb_);
7474
};
7575

7676
/**
77-
* @brief Read and write input.output registers at once
77+
* @brief Reads and writes input/output registers at once.
7878
*
7979
* @param none
80-
* @return none
81-
* @note see status on success, exception thrown in case of communication issues
80+
* @return None.
81+
* @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
8282
*/
8383
void read_write_registers() {
8484
/**
@@ -92,7 +92,7 @@ class Communication{
9292
* @param int read_nb
9393
* @param uint16_t *dest
9494
* @return int >0 on success
95-
* @note see status on success, exception thrown in case of communication issues
95+
* @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
9696
*/
9797
modbus_write_and_read_registers(mb_,
9898
GRIPPER_INPUT_FIRST_REG,
@@ -104,58 +104,58 @@ class Communication{
104104
};
105105

106106
/**
107-
* @brief Set output bytes to zeros
107+
* @brief Sets output bytes to zeros.
108108
*
109109
* @param none
110-
* @return none
111-
* @note see status on success, exception thrown in case of communication issues
110+
* @return None.
111+
* @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
112112
*/
113113
void clear_output_bytes() {
114114
memset(output_bytes_, 0, sizeof(output_bytes_));
115115
};
116116

117117
/**
118-
* @brief Get input byte value
118+
* @brief Retrieves the input byte value at the specified index.
119119
*
120-
* @param index InputBytes byte index
121-
* @return requested byte value
122-
* @note see status on success, exception thrown in case of communication issues
120+
* @param index The InputBytes byte index.
121+
* @return Requested byte value.
122+
* @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
123123
*/
124124
uint8_t get_input_byte(InputBytes index) {
125125
return input_bytes_[(uint)index];
126126
};
127127

128128
/**
129-
* @brief Set output byte value
129+
* @brief Sets the output byte value at the specified index.
130130
*
131131
* @param index OutputBytes byte index
132-
* @param value to be set
132+
* @param value The value to be set.
133133
* @return none
134-
* @note see status on success, exception thrown in case of communication issues
134+
* @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
135135
*/
136136
void set_output_byte(OutputBytes index, uint8_t value) {
137137
output_bytes_[(uint)index] = value;
138138
};
139139

140140
/**
141-
* @brief Set n-th bit to action request byte
141+
* @brief Sets the n-th bit of the action request byte.
142142
*
143143
* @param position_bit n-th bit in byte
144-
* @param value bool value
145-
* @return none
144+
* @param value The boolean value to set for the bit.
145+
* @return None.
146146
*/
147147
void write_action_bit(uint8_t position_bit, bool value) {
148148
output_bytes_[(uint)OutputBytes::ACTION_REQUEST] = bit_set_to(
149149
output_bytes_[(uint)OutputBytes::ACTION_REQUEST], position_bit, value);
150150
};
151151

152152
/**
153-
* @brief Set n-th bit to x value
153+
* @brief Sets the n-th bit of a number to the specified boolean value.
154154
*
155155
* @param number
156-
* @param n n-th bit in number
157-
* @param x bool value
158-
* @return uint number with n-th bit set to x
156+
* @param n The n-th bit position to set.
157+
* @param x The boolean value to set the bit to.
158+
* @return The modified number with the n-th bit set to the specified value.
159159
*/
160160
uint bit_set_to(uint number, uint n, bool x) {
161161
return (number & ~((uint)1 << n)) | ((uint)x << n);

0 commit comments

Comments
 (0)