Skip to content

Commit 1aa0dd3

Browse files
committed
CHG: constant values in screaming case
1 parent e4b0803 commit 1aa0dd3

File tree

6 files changed

+42
-42
lines changed

6 files changed

+42
-42
lines changed

robotiq_hande_driver/include/application.hpp

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -9,12 +9,12 @@
99
namespace hande_driver
1010
{
1111

12-
constexpr auto kGripperPositionMin = 0.0;
13-
constexpr auto kGripperPositionMax = 0.05;
14-
constexpr auto kGripperPositionStep = (kGripperPositionMax - kGripperPositionMin) / 255.0;
15-
constexpr auto kGripperCurrentScale = 0.01;
16-
constexpr auto kMaxSpeed = 255;
17-
constexpr auto kMaxForce = 255;
12+
constexpr auto GRIPPER_POSITION_MIN = 0.0;
13+
constexpr auto GRIPPER_POSITION_MAX = 0.05;
14+
constexpr auto GRIPPER_POSITION_STEP = (GRIPPER_POSITION_MAX - GRIPPER_POSITION_MIN) / 255.0;
15+
constexpr auto GRIPPER_CURRENT_SCALE = 0.01;
16+
constexpr auto MAX_SPEED = 255;
17+
constexpr auto MAX_FORCE = 255;
1818

1919
/**
2020
* @brief This class contains high level gripper commands and status
@@ -92,7 +92,7 @@ class ApplicationLayer{
9292
* @note see status on success, exception thrown if communicatoin issues
9393
*/
9494
void open() {
95-
set_position(kGripperPositionMax);
95+
set_position(GRIPPER_POSITION_MAX);
9696
};
9797

9898
/**
@@ -103,7 +103,7 @@ class ApplicationLayer{
103103
* @note see status on success, exception thrown if communicatoin issues
104104
*/
105105
void close() {
106-
set_position(kGripperPositionMin);
106+
set_position(GRIPPER_POSITION_MIN);
107107
};
108108

109109
/**
@@ -159,7 +159,7 @@ class ApplicationLayer{
159159
*/
160160
void set_position(double position) {
161161
protocol_logic_.go_to(
162-
(uint8_t)((kGripperPositionMax - position) / kGripperPositionStep), kMaxSpeed, kMaxForce);
162+
(uint8_t)((GRIPPER_POSITION_MAX - position) / GRIPPER_POSITION_STEP), MAX_SPEED, MAX_FORCE);
163163
};
164164

165165
/**

robotiq_hande_driver/include/communication.hpp

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -5,19 +5,19 @@
55
#include <string.h>
66

77

8-
namespace hande_driver
8+
namespace hande_driver
99
{
1010

11-
constexpr auto kDeviceName = "/tmp/ttyUR";
12-
constexpr auto kBaudrate = 115200;
13-
constexpr auto kParity = 'N';
14-
constexpr auto kDataBits = 8;
15-
constexpr auto kStopBit = 1;
16-
constexpr auto kDebugModbus = true;
17-
constexpr uint8_t kSlaveID = 0x09;
11+
constexpr auto DEVICE_NAME = "/tmp/ttyUR";
12+
constexpr auto BAUDRATE = 115200;
13+
constexpr auto PARITY = 'N';
14+
constexpr auto DATA_BITS = 8;
15+
constexpr auto STOP_BIT = 1;
16+
constexpr auto DEBUG_MODBUS = true;
17+
constexpr uint8_t SLAVE_ID = 0x09;
1818

19-
constexpr uint16_t kGripperOutputFirstReg = 0x07D0;
20-
constexpr uint16_t kGripperInputFirstReg = 0x03E8;
19+
constexpr uint16_t GRIPPER_OUTPUT_FIRST_REG = 0x07D0;
20+
constexpr uint16_t GRIPPER_INPUT_FIRST_REG = 0x03E8;
2121

2222
constexpr auto kRegisterWordLength = 3;
2323
enum class OutputBytes : uint8_t {
@@ -95,10 +95,10 @@ class Communication{
9595
* @note see status on success, exception thrown in case of communication issues
9696
*/
9797
modbus_write_and_read_registers(mb_,
98-
kGripperInputFirstReg,
98+
GRIPPER_INPUT_FIRST_REG,
9999
kRegisterWordLength,
100100
(uint16_t *)output_bytes_,
101-
kGripperOutputFirstReg,
101+
GRIPPER_OUTPUT_FIRST_REG,
102102
kRegisterWordLength,
103103
(uint16_t *)input_bytes_);
104104
};

robotiq_hande_driver/include/protocol_logic.hpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -80,8 +80,8 @@ enum class ObjectDetectionStatus : uint8_t {
8080
REQ_POS_NO_OBJECT
8181
};
8282

83-
constexpr auto kGripperPositionOpenedThreshold = 230;
84-
constexpr auto kGripperPositionClosedThreshold = 13;
83+
constexpr auto GRIPPER_POSITION_OPENED_THRESHOLD = 230;
84+
constexpr auto GRIPPER_POSITION_CLOSED_THRESHOLD = 13;
8585

8686
/**
8787
* @brief This class contains protocol oriented functions and definitions
@@ -216,7 +216,7 @@ class ProtocolLogic{
216216
* @return True if gripper is closed
217217
*/
218218
bool is_closed() {
219-
return position_ >= kGripperPositionOpenedThreshold;
219+
return position_ >= GRIPPER_POSITION_OPENED_THRESHOLD;
220220
};
221221

222222
/**
@@ -225,7 +225,7 @@ class ProtocolLogic{
225225
* @return True if gripper is opened
226226
*/
227227
bool is_opened() {
228-
return position_ <= kGripperPositionClosedThreshold;
228+
return position_ <= GRIPPER_POSITION_CLOSED_THRESHOLD;
229229
};
230230

231231
/**

robotiq_hande_driver/src/application.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -25,8 +25,8 @@ void ApplicationLayer::read(){
2525

2626
//fault_status
2727

28-
requested_position_ = kGripperPositionMax - (double)protocol_logic_.get_reg_pos() * kGripperPositionStep;
29-
position_ = kGripperPositionMax - (double)protocol_logic_.get_pos() * kGripperPositionStep;
30-
current_ = (double)protocol_logic_.get_current() * kGripperCurrentScale;
28+
requested_position_ = GRIPPER_POSITION_MAX - (double)protocol_logic_.get_reg_pos() * GRIPPER_POSITION_STEP;
29+
position_ = GRIPPER_POSITION_MAX - (double)protocol_logic_.get_pos() * GRIPPER_POSITION_STEP;
30+
current_ = (double)protocol_logic_.get_current() * GRIPPER_CURRENT_SCALE;
3131
}
3232
} // namespace hande_driver

robotiq_hande_driver/src/communication.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -9,9 +9,9 @@ Communication::Communication()
99
: input_bytes_{}
1010
, output_bytes_{}
1111
{
12-
mb_ = modbus_new_rtu(kDeviceName, kBaudrate, kParity, kDataBits, kStopBit);
13-
modbus_set_slave(mb_, kSlaveID);
14-
modbus_set_debug(mb_, kDebugModbus);
12+
mb_ = modbus_new_rtu(DEVICE_NAME, BAUDRATE, PARITY, DATA_BITS, STOP_BIT);
13+
modbus_set_slave(mb_, SLAVE_ID);
14+
modbus_set_debug(mb_, DEBUG_MODBUS);
1515
connect();
1616
}
1717

@@ -21,7 +21,7 @@ void Communication::connect(){
2121

2222
modbus_connect(mb_);
2323

24-
result = modbus_read_registers(mb_, kGripperOutputFirstReg, 1, activation_status);
24+
result = modbus_read_registers(mb_, GRIPPER_OUTPUT_FIRST_REG, 1, activation_status);
2525

2626
if (result > 0) {
2727
printf("Connected successfully: %d\n", result);

robotiq_hande_driver/src/communication_test.cpp

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -2,23 +2,23 @@
22
#include <unistd.h>
33
#include <modbus/modbus.h>
44

5-
constexpr auto kRegisterReadLength = 32;
6-
constexpr auto kDeviceName = "/tmp/ttyUR";
7-
constexpr auto kBaudrate = 115200;
8-
constexpr auto kParity = 'N';
9-
constexpr auto kDataBits = 8;
10-
constexpr auto kStopBit = 1;
11-
constexpr auto kDebugModbus = true;
5+
constexpr auto REGISTER_READ_LENGTH = 32;
6+
constexpr auto DEVICE_NAME = "/tmp/ttyUR";
7+
constexpr auto BAUDRATE = 115200;
8+
constexpr auto PARITY = 'N';
9+
constexpr auto DATA_BITS = 8;
10+
constexpr auto STOP_BIT = 1;
11+
constexpr auto DEBUG_MODBUS = true;
1212

1313
constexpr uint8_t SERVER_ID = 0x09;
1414

1515
int main(void) {
1616
modbus_t *mb;
17-
uint16_t tab_reg[kRegisterReadLength];
17+
uint16_t tab_reg[REGISTER_READ_LENGTH];
1818

19-
mb = modbus_new_rtu(kDeviceName, kBaudrate, kParity, kDataBits, kStopBit);
19+
mb = modbus_new_rtu(DEVICE_NAME, BAUDRATE, PARITY, DATA_BITS, STOP_BIT);
2020
modbus_set_slave(mb, SERVER_ID);
21-
modbus_set_debug(mb, kDebugModbus);
21+
modbus_set_debug(mb, DEBUG_MODBUS);
2222
modbus_connect(mb);
2323
printf("\nConnected\n");
2424

0 commit comments

Comments
 (0)