Skip to content

Commit 97b1381

Browse files
committed
CHG: static cast
1 parent 4c45f9e commit 97b1381

File tree

5 files changed

+31
-26
lines changed

5 files changed

+31
-26
lines changed

robotiq_hande_driver/include/communication.hpp

Lines changed: 10 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
#define COMMUNICATION_HPP_
33

44
#include <modbus/modbus.h>
5-
#include <string.h>
5+
#include <cstring>
66

77

88
namespace hande_driver
@@ -112,7 +112,7 @@ class Communication{
112112
*/
113113
void clear_output_bytes() {
114114
memset(output_bytes_, 0, sizeof(output_bytes_));
115-
};
115+
};
116116

117117
/**
118118
* @brief Retrieves the input byte value at the specified index.
@@ -122,7 +122,7 @@ class Communication{
122122
* @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) {
125-
return input_bytes_[(uint)index];
125+
return input_bytes_[static_cast<uint>(index)];
126126
};
127127

128128
/**
@@ -134,7 +134,7 @@ class Communication{
134134
* @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) {
137-
output_bytes_[(uint)index] = value;
137+
output_bytes_[static_cast<uint>(index)] = value;
138138
};
139139

140140
/**
@@ -145,8 +145,8 @@ class Communication{
145145
* @return None.
146146
*/
147147
void write_action_bit(uint8_t position_bit, bool value) {
148-
output_bytes_[(uint)OutputBytes::ACTION_REQUEST] = bit_set_to(
149-
output_bytes_[(uint)OutputBytes::ACTION_REQUEST], position_bit, value);
148+
output_bytes_[static_cast<uint>(OutputBytes::ACTION_REQUEST)] = bit_set_to(
149+
output_bytes_[static_cast<uint>(OutputBytes::ACTION_REQUEST)], position_bit, value);
150150
};
151151

152152
/**
@@ -157,8 +157,10 @@ class Communication{
157157
* @param x The boolean value to set the bit to.
158158
* @return The modified number with the n-th bit set to the specified value.
159159
*/
160-
uint bit_set_to(uint number, uint n, bool x) {
161-
return (number & ~((uint)1 << n)) | ((uint)x << n);
160+
uint bit_set_to(uint value, uint n, bool x) {
161+
uint reset_n_bit = ~(1u << n);
162+
uint set_n_bit = static_cast<uint>(x) << n;
163+
return (value & reset_n_bit) | set_n_bit;
162164
};
163165

164166
private:

robotiq_hande_driver/include/protocol_logic.hpp

Lines changed: 14 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@ enum class AutoReleaseDirection : uint8_t {
3737
OPENING
3838
};
3939

40-
// Gripper Status
40+
/* Gripper Status */
4141
enum class ResponseByte : uint8_t {
4242
STATUS = 0u,
4343
FAULT_STATUS = 2u,
@@ -52,27 +52,27 @@ enum class StatusPositionBit : uint8_t {
5252
OBJECT_DETECTION_STATUS = 6u, /* gObj */
5353
};
5454

55-
constexpr auto kActivationStatusBits = 0b1;
55+
constexpr auto ACTIVATION_STATUS_BITS = 0b1;
5656
enum class ActivationStatus : uint8_t {
5757
GRIPPER_RESET = 0u,
5858
GRIPPER_ACTIVATION
5959
};
6060

61-
constexpr auto kActionStatusBits = 0b1;
61+
constexpr auto ACTION_STATUS_BITS = 0b1;
6262
enum class ActionStatus : uint8_t {
6363
STOPPED = 0u,
6464
GO_TO_POSITION_REQUEST
6565
};
6666

67-
constexpr auto kGripperStatusBits = 0b11;
67+
constexpr auto GRIPPER_STATUS_BITS = 0b11;
6868
enum class GripperStatus : uint8_t {
6969
GRIPPER_IN_RESET = 0u,
7070
ACTIVATION_IN_PROGRESS,
7171
NOT_USED,
7272
ACTIVATION_COMPLETE
7373
};
7474

75-
constexpr auto kObjectDetectionStatusBits = 0b11;
75+
constexpr auto OBJECT_DETECTION_STATUS_BITS = 0b11;
7676
enum class ObjectDetectionStatus : uint8_t {
7777
MOTION_NO_OBJECT = 0u,
7878
STOPPED_OPENING_DETECTED,
@@ -114,7 +114,7 @@ class ProtocolLogic{
114114
*/
115115
void set() {
116116
communication_.clear_output_bytes();
117-
communication_.write_action_bit((uint)ActionRequestPositionBit::ACTIVATE, (bool)Activate::ACTIVATE_GRIPPER);
117+
communication_.write_action_bit(static_cast<uint>(ActionRequestPositionBit::ACTIVATE), static_cast<bool>(Activate::ACTIVATE_GRIPPER));
118118
communication_.read_write_registers();
119119
};
120120

@@ -126,8 +126,10 @@ class ProtocolLogic{
126126
* @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
127127
*/
128128
void auto_release() {
129-
communication_.write_action_bit((uint)ActionRequestPositionBit::AUTOMATIC_RELEASE, (bool)AutomaticRelease::EMERGENCY_AUTO_RELEASE);
130-
communication_.write_action_bit((uint)ActionRequestPositionBit::AUTOMATIC_RELEASE_DIRECTION, (bool)AutoReleaseDirection::OPENING);
129+
communication_.write_action_bit(
130+
static_cast<uint>(ActionRequestPositionBit::AUTOMATIC_RELEASE), static_cast<bool>(AutomaticRelease::EMERGENCY_AUTO_RELEASE));
131+
communication_.write_action_bit(
132+
static_cast<uint>(ActionRequestPositionBit::AUTOMATIC_RELEASE_DIRECTION), static_cast<bool>(AutoReleaseDirection::OPENING));
131133
communication_.read_write_registers();
132134
};
133135

@@ -153,7 +155,8 @@ class ProtocolLogic{
153155
* @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
154156
*/
155157
void go_to(uint8_t position, uint8_t velocity, uint8_t force) {
156-
communication_.write_action_bit((uint)ActionRequestPositionBit::GO_TO, (bool)GoTo::GO_TO_REQ_POS);
158+
communication_.write_action_bit(
159+
static_cast<uint>(ActionRequestPositionBit::GO_TO), static_cast<bool>(GoTo::GO_TO_REQ_POS));
157160
communication_.set_output_byte(OutputBytes::POSITION_REQUEST, position);
158161
communication_.set_output_byte(OutputBytes::SPEED, velocity);
159162
communication_.set_output_byte(OutputBytes::FORCE, force);
@@ -167,7 +170,8 @@ class ProtocolLogic{
167170
* @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
168171
*/
169172
void stop() {
170-
communication_.write_action_bit((uint)ActionRequestPositionBit::GO_TO, (bool)GoTo::STOP);
173+
communication_.write_action_bit(
174+
static_cast<uint>(ActionRequestPositionBit::GO_TO), static_cast<bool>(GoTo::STOP));
171175
communication_.read_write_registers();
172176
};
173177

robotiq_hande_driver/src/communication.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -23,10 +23,9 @@ void Communication::connect(){
2323

2424
result = modbus_read_registers(mb_, GRIPPER_OUTPUT_FIRST_REG, 1, activation_status);
2525

26-
if (result > 0) {
26+
if (result > 0)
2727
printf("Connected successfully: %d\n", result);
28-
} else {
28+
else
2929
printf("Couldn't connect: %d\n", result);
30-
}
3130
}
3231
} // namespace hande_driver

robotiq_hande_driver/src/communication_test.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -59,7 +59,7 @@ void wait_activation_complete(modbus_t *ctx){
5959
while (activation_status[0] != GRIPPER_FLAGS_ACTIVATED){
6060
printf("Gripper not yet activated: %.4X vs. %.4X\n", activation_status[0], GRIPPER_FLAGS_ACTIVATED);
6161
modbus_read_registers(ctx, GRIPPER_OUTPUT_FIRST_REG, 1, activation_status);
62-
62+
6363
}
6464
}
6565

robotiq_hande_driver/src/protocol_logic.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -25,16 +25,16 @@ void ProtocolLogic::refresh_registers(){
2525
status_ = communication_.get_input_byte(InputBytes::GRIPPER_STATUS);
2626

2727
activation_status_ = (ActivationStatus)(
28-
(status_>>(uint)StatusPositionBit::ACTIVATION_STATUS) & kActivationStatusBits);
28+
(status_>>static_cast<uint>(StatusPositionBit::ACTIVATION_STATUS)) & ACTIVATION_STATUS_BITS);
2929

3030
action_status_ = (ActionStatus)(
31-
(status_>>(uint)StatusPositionBit::ACTION_STATUS) & kActionStatusBits);
31+
(status_>>static_cast<uint>(StatusPositionBit::ACTION_STATUS)) & ACTION_STATUS_BITS);
3232

3333
gripper_status_ = (GripperStatus)(
34-
(status_>>(uint)StatusPositionBit::GRIPPER_STATUS) & kGripperStatusBits);
34+
(status_>>static_cast<uint>(StatusPositionBit::GRIPPER_STATUS)) & GRIPPER_STATUS_BITS);
3535

3636
object_detection_status_ = (ObjectDetectionStatus)(
37-
(status_>>(uint)StatusPositionBit::OBJECT_DETECTION_STATUS) & kObjectDetectionStatusBits);
37+
(status_>>static_cast<uint>(StatusPositionBit::OBJECT_DETECTION_STATUS)) & OBJECT_DETECTION_STATUS_BITS);
3838

3939
fault_status_ = communication_.get_input_byte(InputBytes::FAULT_STATUS);
4040
//To bo specified

0 commit comments

Comments
 (0)