Skip to content

Commit 3e24a13

Browse files
committed
CHG: code according to review - position bits, getters
1 parent 988b8c2 commit 3e24a13

File tree

6 files changed

+55
-59
lines changed

6 files changed

+55
-59
lines changed

robotiq_hande_driver/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@ add_executable(hande_driver src/hande_driver.cpp src/application.cpp src/protoco
1616
target_link_libraries(hande_driver ${catkin_LIBRARIES})
1717
target_link_libraries(hande_driver /lib/x86_64-linux-gnu/libmodbus.so)
1818

19-
add_executable(communication_test src/communication_test.c)
19+
add_executable(communication_test src/communication_test.cpp)
2020
target_link_libraries(communication_test ${catkin_LIBRARIES})
2121
target_link_libraries(communication_test /lib/x86_64-linux-gnu/libmodbus.so)
2222

robotiq_hande_driver/include/application.hpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@ class ApplicationLayer{
3939
*
4040
* @param none
4141
* @return none
42-
* @note see status on success, exception thrown if communicatoin issues
42+
* @note The status should be checked to verify successful execution. An exception is thrown if communication issues occur.
4343
*/
4444
void stop();
4545

@@ -113,7 +113,7 @@ class ApplicationLayer{
113113
* @return Gripper requested position
114114
* @note see status on success, exception thrown if communicatoin issues
115115
*/
116-
double requested_position();
116+
double get_requested_position();
117117

118118
/**
119119
* @brief Returns the gripper position
@@ -122,7 +122,7 @@ class ApplicationLayer{
122122
* @return Gripper position in [m]
123123
* @note see status on success, exception thrown if communicatoin issues
124124
*/
125-
double position();
125+
double get_position();
126126

127127
/**
128128
* @brief Moves the gripper to requested position
@@ -140,7 +140,7 @@ class ApplicationLayer{
140140
* @return Gripper current in [A] (range: 0-2.55A)
141141
* @note see status on success, exception thrown if communicatoin issues
142142
*/
143-
double current();
143+
double get_current();
144144

145145

146146
void read();

robotiq_hande_driver/include/protocol_logic.hpp

Lines changed: 23 additions & 35 deletions
Original file line numberDiff line numberDiff line change
@@ -7,65 +7,63 @@
77
namespace hande_driver
88
{
99

10-
// Action Request
11-
constexpr uint8_t kActionRequestByte = 0;
12-
constexpr uint8_t kActivatePositionByte = 0; // rACT
10+
/* Register mapping done based on Hand-E documentation:
11+
* https://assets.robotiq.com/website-assets/support_documents/document/Hand-E_Instruction_Manual_e-Series_PDF_20190306.pdf
12+
*/
13+
enum class ActionRequestPositionBit : uint8_t {
14+
ACTIVATE = 0u, /* rACT */
15+
GO_TO = 3u, /* rGTO */
16+
AUTOMATIC_RELEASE = 4u, /* rATR */
17+
AUTOMATIC_RELEASE_DIRECTION = 5u, /* rARD */
18+
};
19+
1320
enum class Activate : uint8_t {
1421
DEACTIVATE_GRIPPER = 0u,
1522
ACTIVATE_GRIPPER
1623
};
1724

18-
constexpr uint8_t kGoToPositionByte = 3; // rGTO
1925
enum class GoTo : uint8_t {
2026
STOP = 0u,
2127
GO_TO_REQ_POS
2228
};
2329

24-
constexpr uint8_t kAutomaticReleasePositionByte = 4; // rATR
2530
enum class AutomaticRelease : uint8_t {
2631
NORMAL = 0u,
2732
EMERGENCY_AUTO_RELEASE
2833
};
2934

30-
constexpr uint8_t kAutoReleaseDirectionPositionByte = 5; // rARD
3135
enum class AutoReleaseDirection : uint8_t {
3236
CLOSING = 0u,
3337
OPENING
3438
};
3539

36-
//Position Request
37-
constexpr uint8_t kPositionRequestByte = 3;
38-
// 0x00 - Open position, with 50 mm opening
39-
// 0xFF - Closed
40-
// Opening / count: ≈0.2 mm for 50 mm stroke
41-
42-
//Speed Request
43-
constexpr uint8_t kSpeedRequestByte = 4;
44-
// 0x00 - Minimum speed
45-
// 0xFF - Maximum speed
40+
// Gripper Status
41+
enum class ResponseByte : uint8_t {
42+
STATUS = 0u,
43+
FAULT_STATUS = 2u,
44+
SPEED = 4u,
45+
FORCE = 5u,
46+
};
4647

47-
//Force Request
48-
constexpr uint8_t kForceRequestByte = 5;
49-
// 0x00 - Minimum force
50-
// 0xFF - Maximum force
48+
enum class StatusPositionBit : uint8_t {
49+
ACTIVATION_STATUS = 0u, /* gACT */
50+
ACTION_STATUS = 3u, /* gGTO */
51+
GRIPPER_STATUS = 4u, /* gSTA */
52+
OBJECT_DETECTION_STATUS = 6u, /* gObj */
53+
};
5154

52-
// Gripper Status
53-
constexpr uint8_t kStatusByte = 0;
54-
constexpr uint8_t kActivationStatusPositionByte = 0; // gACT
5555
constexpr auto kActivationStatusBits = 0b1;
5656
enum class ActivationStatus : uint8_t {
5757
GRIPPER_RESET = 0u,
5858
GRIPPER_ACTIVATION
5959
};
6060

61-
constexpr uint8_t kActionStatusPositionByte = 3; // gGTO
6261
constexpr auto kActionStatusBits = 0b1;
6362
enum class ActionStatus : uint8_t {
6463
STOPPED = 0u,
6564
GO_TO_POSITION_REQUEST
6665
};
6766

68-
constexpr uint8_t kGripperStatusPositionByte = 4; // gSTA
6967
constexpr auto kGripperStatusBits = 0b11;
7068
enum class GripperStatus : uint8_t {
7169
GRIPPER_IN_RESET = 0u,
@@ -74,7 +72,6 @@ enum class GripperStatus : uint8_t {
7472
ACTIVATION_COMPLETE
7573
};
7674

77-
constexpr uint8_t kObjectDetectionStatusPositionByte = 6; // gObj
7875
constexpr auto kObjectDetectionStatusBits = 0b11;
7976
enum class ObjectDetectionStatus : uint8_t {
8077
MOTION_NO_OBJECT = 0u,
@@ -83,15 +80,6 @@ enum class ObjectDetectionStatus : uint8_t {
8380
REQ_POS_NO_OBJECT
8481
};
8582

86-
// Fault Status
87-
constexpr uint8_t kFaultStatusByte = 2;
88-
// Position Request Echo
89-
constexpr uint8_t kPositionRequestEchoByte = 3;
90-
// Position (current)
91-
constexpr uint8_t kPositionByte = 4;
92-
// Current
93-
constexpr uint8_t kCurrentByte = 5;
94-
9583

9684
/**
9785
* @brief This class contains protocol oriented functions and definitions

robotiq_hande_driver/src/application.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -13,9 +13,9 @@ constexpr auto kMaxSpeed = 255;
1313
constexpr auto kMaxForce = 255;
1414

1515
ApplicationLayer::ApplicationLayer()
16-
: requested_position_(0)
17-
, position_(0)
18-
, current_(0)
16+
: requested_position_()
17+
, position_()
18+
, current_()
1919
{
2020
printf("ApplicationLayer constructor\n");
2121
}
@@ -60,11 +60,11 @@ ApplicationLayer::FaultStatus ApplicationLayer::get_fault_status(){
6060
return fault_status_;
6161
}
6262

63-
double ApplicationLayer::requested_position(){
63+
double ApplicationLayer::get_requested_position(){
6464
return requested_position_;
6565
}
6666

67-
double ApplicationLayer::position(){
67+
double ApplicationLayer::get_position(){
6868
return position_;
6969
}
7070

@@ -74,7 +74,7 @@ void ApplicationLayer::set_position(double position){
7474
protocol_logic_.go_to(raw_position, kMaxSpeed, kMaxForce);
7575
}
7676

77-
double ApplicationLayer::current(){
77+
double ApplicationLayer::get_current(){
7878
return current_;
7979
}
8080

robotiq_hande_driver/src/communication_test.cpp

Lines changed: 11 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -2,15 +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;
12+
513
constexpr uint8_t SERVER_ID = 0x09;
614

715
int main(void) {
816
modbus_t *mb;
9-
uint16_t tab_reg[32];
17+
uint16_t tab_reg[kRegisterReadLength];
1018

11-
mb = modbus_new_rtu("/tmp/ttyUR", 115200, 'N', 8, 1);
19+
mb = modbus_new_rtu(kDeviceName, kBaudrate, kParity, kDataBits, kStopBit);
1220
modbus_set_slave(mb, SERVER_ID);
13-
modbus_set_debug(mb, TRUE);
21+
modbus_set_debug(mb, kDebugModbus);
1422
modbus_connect(mb);
1523
printf("\nConnected\n");
1624

robotiq_hande_driver/src/protocol_logic.cpp

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -29,22 +29,22 @@ ProtocolLogic::~ProtocolLogic(){
2929
void ProtocolLogic::reset(){
3030
communication_.clear_output_bytes();
3131

32-
communication_.write_action_bit(kActivatePositionByte, (bool)Activate::DEACTIVATE_GRIPPER);
32+
communication_.write_action_bit((uint)ActionRequestPositionBit::ACTIVATE, (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, (bool)Activate::ACTIVATE_GRIPPER);
40+
communication_.write_action_bit((uint)ActionRequestPositionBit::ACTIVATE, (bool)Activate::ACTIVATE_GRIPPER);
4141

4242
communication_.read_write_registers();
4343
}
4444

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

4949
communication_.read_write_registers();
5050
}
@@ -55,7 +55,7 @@ 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, (bool)GoTo::GO_TO_REQ_POS);
58+
communication_.write_action_bit((uint)ActionRequestPositionBit::GO_TO, (bool)GoTo::GO_TO_REQ_POS);
5959

6060
communication_.set_output_byte(OutputBytes::POSITION_REQUEST, position);
6161
communication_.set_output_byte(OutputBytes::SPEED, velocity);
@@ -65,7 +65,7 @@ void ProtocolLogic::go_to(uint8_t position, uint8_t velocity, uint8_t force){
6565
}
6666

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

7070
communication_.read_write_registers();
7171
}
@@ -120,16 +120,16 @@ void ProtocolLogic::refresh_registers(){
120120
status_ = communication_.get_input_byte(InputBytes::GRIPPER_STATUS);
121121

122122
activation_status_ = (ActivationStatus)(
123-
(status_>>kActivationStatusPositionByte) & kActivationStatusBits);
123+
(status_>>(uint)StatusPositionBit::ACTIVATION_STATUS) & kActivationStatusBits);
124124

125125
action_status_ = (ActionStatus)(
126-
(status_>>kActionStatusPositionByte) & kActionStatusBits);
126+
(status_>>(uint)StatusPositionBit::ACTION_STATUS) & kActionStatusBits);
127127

128128
gripper_status_ = (GripperStatus)(
129-
(status_>>kGripperStatusPositionByte) & kGripperStatusBits);
129+
(status_>>(uint)StatusPositionBit::GRIPPER_STATUS) & kGripperStatusBits);
130130

131131
object_detection_status_ = (ObjectDetectionStatus)(
132-
(status_>>kObjectDetectionStatusPositionByte) & kObjectDetectionStatusBits);
132+
(status_>>(uint)StatusPositionBit::OBJECT_DETECTION_STATUS) & kObjectDetectionStatusBits);
133133

134134
fault_status_ = communication_.get_input_byte(InputBytes::FAULT_STATUS);
135135
//To bo specified

0 commit comments

Comments
 (0)