Skip to content

Commit 988b8c2

Browse files
committed
CHG: code according to review
1 parent d681943 commit 988b8c2

File tree

6 files changed

+67
-70
lines changed

6 files changed

+67
-70
lines changed

robotiq_hande_driver/include/application.hpp

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -5,13 +5,14 @@
55

66
#include "protocol_logic.hpp"
77

8-
/**
9-
* @brief This class contains high level gripper commands and status
10-
*/
118

129
namespace hande_driver
1310
{
1411

12+
13+
/**
14+
* @brief This class contains high level gripper commands and status
15+
*/
1516
class ApplicationLayer{
1617
public:
1718

robotiq_hande_driver/include/communication.hpp

Lines changed: 20 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -1,38 +1,36 @@
11
#ifndef COMMUNICATION_HPP_
22
#define COMMUNICATION_HPP_
33

4-
#include <stdint.h>
5-
#include <stddef.h>
6-
#include <vector>
74
#include <modbus/modbus.h>
85

9-
/**
10-
* @brief This class contains low level gripper commands and status
11-
*/
126

137
namespace hande_driver
148
{
159
constexpr auto kRegisterWordLength = 3;
1610
enum class OutputBytes : uint8_t {
17-
OUTPUT_BYTES_RESERVED_1 = 0u,
18-
OUTPUT_BYTES_ACTION_REQUEST,
19-
OUTPUT_BYTES_POSITION_REQUEST,
20-
OUTPUT_BYTES_RESERVED_2,
21-
OUTPUT_BYTES_FORCE,
22-
OUTPUT_BYTES_SPEED,
23-
OUTPUT_BYTES_MAX
11+
RESERVED_1 = 0u,
12+
ACTION_REQUEST,
13+
POSITION_REQUEST,
14+
RESERVED_2,
15+
FORCE,
16+
SPEED,
17+
BYTES_MAX
2418
};
2519

2620
enum class InputBytes : uint8_t {
27-
INPUT_BYTES_RESERVED_1 = 0u,
28-
INPUT_BYTES_GRIPPER_STATUS,
29-
INPUT_BYTES_POSITION_REQUEST_ECHO,
30-
INPUT_BYTES_FAULT_STATUS,
31-
INPUT_BYTES_CURRENT,
32-
INPUT_BYTES_POSITION,
33-
INPUT_BYTES_MAX
21+
RESERVED_1 = 0u,
22+
GRIPPER_STATUS,
23+
POSITION_REQUEST_ECHO,
24+
FAULT_STATUS,
25+
CURRENT,
26+
POSITION,
27+
BYTES_MAX
3428
};
3529

30+
31+
/**
32+
* @brief This class contains low level gripper commands and status
33+
*/
3634
class Communication{
3735
public:
3836
Communication();
@@ -116,8 +114,8 @@ class Communication{
116114
private:
117115
modbus_t *mb_;
118116

119-
uint8_t input_bytes_[INPUT_BYTES_MAX];
120-
uint8_t output_bytes_[OUTPUT_BYTES_MAX];
117+
uint8_t input_bytes_[static_cast<size_t>(InputBytes::BYTES_MAX)];
118+
uint8_t output_bytes_[static_cast<size_t>(OutputBytes::BYTES_MAX)];
121119

122120
};
123121
} // namespace hande_driver

robotiq_hande_driver/include/protocol_logic.hpp

Lines changed: 4 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,8 @@
11
#ifndef PROTOCOL_LOGIC_HPP_
22
#define PROTOCOL_LOGIC_HPP_
33

4-
#include <stdint.h>
5-
64
#include <communication.hpp>
75

8-
/**
9-
* @brief This class contains protocol oriented functions and definitions
10-
*/
116

127
namespace hande_driver
138
{
@@ -97,6 +92,10 @@ constexpr uint8_t kPositionByte = 4;
9792
// Current
9893
constexpr uint8_t kCurrentByte = 5;
9994

95+
96+
/**
97+
* @brief This class contains protocol oriented functions and definitions
98+
*/
10099
class ProtocolLogic{
101100
public:
102101
ProtocolLogic();

robotiq_hande_driver/src/communication.cpp

Lines changed: 6 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,6 @@
11
#include "communication.hpp"
22

33
#include <cstdio>
4-
#include <stdint.h>
54
#include <string.h>
65

76

@@ -19,8 +18,8 @@ constexpr uint16_t kGripperOutputFirstReg = 0x07D0;
1918
constexpr uint16_t kGripperInputFirstReg = 0x03E8;
2019

2120
Communication::Communication()
22-
: input_bytes_{0, 0, 0, 0, 0, 0}
23-
, output_bytes_{0, 0, 0, 0, 0, 0}
21+
: input_bytes_{}
22+
, output_bytes_{}
2423
{
2524
printf("Communication constructor\n");
2625
mb_ = modbus_new_rtu(kDeviceName, kBaudrate, kParity, kDataBits, kStopBit);
@@ -82,16 +81,16 @@ void Communication::clear_output_bytes(){
8281
}
8382

8483
uint8_t Communication::get_input_byte(InputBytes index){
85-
return input_bytes_[index];
84+
return input_bytes_[(uint)index];
8685
}
8786

8887
void Communication::set_output_byte(OutputBytes index, uint8_t value){
89-
output_bytes_[index] = value;
88+
output_bytes_[(uint)index] = value;
9089
}
9190

9291
void Communication::write_action_bit(uint8_t position_bit, bool value){
93-
output_bytes_[OUTPUT_BYTES_ACTION_REQUEST] = bit_set_to(
94-
output_bytes_[OUTPUT_BYTES_ACTION_REQUEST], position_bit, value);
92+
output_bytes_[(uint)OutputBytes::ACTION_REQUEST] = bit_set_to(
93+
output_bytes_[(uint)OutputBytes::ACTION_REQUEST], position_bit, value);
9594
}
9695

9796
inline uint Communication::bit_set_to(uint number, uint n, bool x) {

robotiq_hande_driver/src/communication_test.c renamed to robotiq_hande_driver/src/communication_test.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
#include <unistd.h>
33
#include <modbus/modbus.h>
44

5-
#define SERVER_ID 0x09
5+
constexpr uint8_t SERVER_ID = 0x09;
66

77
int main(void) {
88
modbus_t *mb;

robotiq_hande_driver/src/protocol_logic.cpp

Lines changed: 32 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -9,15 +9,15 @@ constexpr auto kGripperPositionOpenedThreshold = 230;
99
constexpr auto kGripperPositionClosedThreshold = 13;
1010

1111
ProtocolLogic::ProtocolLogic()
12-
: status_(0)
13-
, activation_status_(GRIPPER_RESET)
14-
, action_status_(STOPPED)
15-
, gripper_status_(NOT_USED)
16-
, object_detection_status_(REQ_POS_NO_OBJECT)
17-
, fault_status_(0)
18-
, position_request_echo_(0)
19-
, position_(0)
20-
, current_(0)
12+
: status_()
13+
, activation_status_(ActivationStatus::GRIPPER_RESET)
14+
, action_status_(ActionStatus::STOPPED)
15+
, gripper_status_(GripperStatus::NOT_USED)
16+
, object_detection_status_(ObjectDetectionStatus::REQ_POS_NO_OBJECT)
17+
, fault_status_()
18+
, position_request_echo_()
19+
, position_()
20+
, current_()
2121
{
2222
printf("ProtocolLogic constructor\n");
2323
}
@@ -29,22 +29,22 @@ ProtocolLogic::~ProtocolLogic(){
2929
void ProtocolLogic::reset(){
3030
communication_.clear_output_bytes();
3131

32-
communication_.write_action_bit(kActivatePositionByte, DEACTIVATE_GRIPPER);
32+
communication_.write_action_bit(kActivatePositionByte, (bool)Activate::DEACTIVATE_GRIPPER);
3333

3434
communication_.read_write_registers();
3535
}
3636

3737
void ProtocolLogic::set(){
3838
communication_.clear_output_bytes();
3939

40-
communication_.write_action_bit(kActivatePositionByte, ACTIVATE_GRIPPER);
40+
communication_.write_action_bit(kActivatePositionByte, (bool)Activate::ACTIVATE_GRIPPER);
4141

4242
communication_.read_write_registers();
4343
}
4444

4545
void ProtocolLogic::auto_release(){
46-
communication_.write_action_bit(kAutomaticReleasePositionByte, EMERGENCY_AUTO_RELEASE);
47-
communication_.write_action_bit(kAutoReleaseDirectionPositionByte, OPENING);
46+
communication_.write_action_bit(kAutomaticReleasePositionByte, (bool)AutomaticRelease::EMERGENCY_AUTO_RELEASE);
47+
communication_.write_action_bit(kAutoReleaseDirectionPositionByte, (bool)AutoReleaseDirection::OPENING);
4848

4949
communication_.read_write_registers();
5050
}
@@ -55,38 +55,38 @@ void ProtocolLogic::activate(){
5555
}
5656

5757
void ProtocolLogic::go_to(uint8_t position, uint8_t velocity, uint8_t force){
58-
communication_.write_action_bit(kGoToPositionByte, GO_TO_REQ_POS);
58+
communication_.write_action_bit(kGoToPositionByte, (bool)GoTo::GO_TO_REQ_POS);
5959

60-
communication_.set_output_byte(OUTPUT_BYTES_POSITION_REQUEST, position);
61-
communication_.set_output_byte(OUTPUT_BYTES_SPEED, velocity);
62-
communication_.set_output_byte(OUTPUT_BYTES_FORCE, force);
60+
communication_.set_output_byte(OutputBytes::POSITION_REQUEST, position);
61+
communication_.set_output_byte(OutputBytes::SPEED, velocity);
62+
communication_.set_output_byte(OutputBytes::FORCE, force);
6363

6464
communication_.read_write_registers();
6565
}
6666

6767
void ProtocolLogic::stop(){
68-
communication_.write_action_bit(kGoToPositionByte, STOP);
68+
communication_.write_action_bit(kGoToPositionByte, (bool)GoTo::STOP);
6969

7070
communication_.read_write_registers();
7171
}
7272

7373
bool ProtocolLogic::is_reset(){
74-
return (gripper_status_ == GRIPPER_IN_RESET &&
75-
activation_status_ == GRIPPER_RESET);
74+
return (gripper_status_ == GripperStatus::GRIPPER_IN_RESET &&
75+
activation_status_ == ActivationStatus::GRIPPER_RESET);
7676
}
7777

7878
bool ProtocolLogic::is_ready(){
79-
return (gripper_status_ == ACTIVATION_COMPLETE &&
80-
activation_status_ == GRIPPER_ACTIVATION);
79+
return (gripper_status_ == GripperStatus::ACTIVATION_COMPLETE &&
80+
activation_status_ == ActivationStatus::GRIPPER_ACTIVATION);
8181
}
8282

8383
bool ProtocolLogic::is_moving(){
84-
return (action_status_ == GO_TO_POSITION_REQUEST &&
85-
object_detection_status_ == MOTION_NO_OBJECT);
84+
return (action_status_ == ActionStatus::GO_TO_POSITION_REQUEST &&
85+
object_detection_status_ == ObjectDetectionStatus::MOTION_NO_OBJECT);
8686
}
8787

8888
bool ProtocolLogic::is_stopped(){
89-
return object_detection_status_ != MOTION_NO_OBJECT;
89+
return object_detection_status_ != ObjectDetectionStatus::MOTION_NO_OBJECT;
9090
}
9191

9292
bool ProtocolLogic::is_closed(){
@@ -98,8 +98,8 @@ bool ProtocolLogic::is_opened(){
9898
}
9999

100100
bool ProtocolLogic::obj_detected(){
101-
return (object_detection_status_ == STOPPED_OPENING_DETECTED ||
102-
object_detection_status_ == STOPPED_CLOSING_DETECTED);
101+
return (object_detection_status_ == ObjectDetectionStatus::STOPPED_OPENING_DETECTED ||
102+
object_detection_status_ == ObjectDetectionStatus::STOPPED_CLOSING_DETECTED);
103103
}
104104

105105
uint8_t ProtocolLogic::get_reg_pos(){
@@ -117,7 +117,7 @@ uint8_t ProtocolLogic::get_current(){
117117
void ProtocolLogic::refresh_registers(){
118118
communication_.read_write_registers();
119119

120-
status_ = communication_.get_input_byte(INPUT_BYTES_GRIPPER_STATUS);
120+
status_ = communication_.get_input_byte(InputBytes::GRIPPER_STATUS);
121121

122122
activation_status_ = (ActivationStatus)(
123123
(status_>>kActivationStatusPositionByte) & kActivationStatusBits);
@@ -131,11 +131,11 @@ void ProtocolLogic::refresh_registers(){
131131
object_detection_status_ = (ObjectDetectionStatus)(
132132
(status_>>kObjectDetectionStatusPositionByte) & kObjectDetectionStatusBits);
133133

134-
fault_status_ = communication_.get_input_byte(INPUT_BYTES_FAULT_STATUS);
134+
fault_status_ = communication_.get_input_byte(InputBytes::FAULT_STATUS);
135135
//To bo specified
136136

137-
position_request_echo_ = communication_.get_input_byte(INPUT_BYTES_POSITION_REQUEST_ECHO);
138-
position_ = communication_.get_input_byte(INPUT_BYTES_POSITION);
139-
current_ = communication_.get_input_byte(INPUT_BYTES_CURRENT);
137+
position_request_echo_ = communication_.get_input_byte(InputBytes::POSITION_REQUEST_ECHO);
138+
position_ = communication_.get_input_byte(InputBytes::POSITION);
139+
current_ = communication_.get_input_byte(InputBytes::CURRENT);
140140
}
141141
} // namespace hande_driver

0 commit comments

Comments
 (0)