Skip to content

Commit ee47e6e

Browse files
committed
CHG: move write action bit to communication file
1 parent b7477f5 commit ee47e6e

File tree

4 files changed

+34
-37
lines changed

4 files changed

+34
-37
lines changed

robotiq_hande_driver/include/communication.hpp

Lines changed: 19 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -97,6 +97,25 @@ class Communication{
9797
// uint16_t input_registers_[kRegisterWordLength];
9898
// uint16_t output_registers_[kRegisterWordLength];
9999

100+
/**
101+
* @brief Set n-th bit to action request byte
102+
*
103+
* @param position_bit n-th bit in byte
104+
* @param value bool value
105+
* @return none
106+
*/
107+
void write_action_bit(uint8_t position_bit, bool value);
108+
109+
/**
110+
* @brief Set n-th bit to x value
111+
*
112+
* @param number
113+
* @param n n-th bit in number
114+
* @param x bool value
115+
* @return uint number with n-th bit set to x
116+
*/
117+
uint bit_set_to(uint number, uint n, bool x);
118+
100119
private:
101120
modbus_t *mb_;
102121

robotiq_hande_driver/include/protocol_logic.hpp

Lines changed: 0 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -231,25 +231,6 @@ class ProtocolLogic{
231231
*/
232232
void refresh_registers();
233233

234-
/**
235-
* @brief Set n-th bit to action request byte
236-
*
237-
* @param position_bit n-th bit in byte
238-
* @param value bool value
239-
* @return none
240-
*/
241-
void write_action_bit(uint8_t position_bit, bool value);
242-
243-
/**
244-
* @brief Set n-th bit to x value
245-
*
246-
* @param number
247-
* @param n n-th bit in number
248-
* @param x bool value
249-
* @return uint number with n-th bit set to x
250-
*/
251-
uint bit_set_to(uint number, uint n, bool x);
252-
253234
private:
254235
// Gripper
255236
uint8_t status_;

robotiq_hande_driver/src/communication.cpp

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -69,4 +69,13 @@ uint8_t Communication::get_input_byte(InputBytes index){
6969
void Communication::set_output_byte(OutputBytes index, uint8_t value){
7070
output_bytes_[index] = value;
7171
}
72+
73+
void Communication::write_action_bit(uint8_t position_bit, bool value){
74+
output_bytes_[OUTPUT_BYTES_ACTION_REQUEST] = bit_set_to(
75+
output_bytes_[OUTPUT_BYTES_ACTION_REQUEST], 8 + position_bit, value);
76+
}
77+
78+
inline uint Communication::bit_set_to(uint number, uint n, bool x) {
79+
return (number & ~((uint)1 << n)) | ((uint)x << n);
80+
}
7281
} // namespace hande_driver

robotiq_hande_driver/src/protocol_logic.cpp

Lines changed: 6 additions & 18 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-
write_action_bit(kActivatePositionByte, DEACTIVATE_GRIPPER);
32+
communication_.write_action_bit(kActivatePositionByte, DEACTIVATE_GRIPPER);
3333

3434
communication_.read_write_registers();
3535
}
3636

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

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

4242
communication_.read_write_registers();
4343
}
4444

4545
void ProtocolLogic::auto_release(){
46-
write_action_bit(kAutomaticReleasePositionByte, EMERGENCY_AUTO_RELEASE);
47-
write_action_bit(kAutoReleaseDirectionPositionByte, OPENING);
46+
communication_.write_action_bit(kAutomaticReleasePositionByte, EMERGENCY_AUTO_RELEASE);
47+
communication_.write_action_bit(kAutoReleaseDirectionPositionByte, 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-
write_action_bit(kGoToPositionByte, GO_TO_REQ_POS);
58+
communication_.write_action_bit(kGoToPositionByte, GO_TO_REQ_POS);
5959

6060
communication_.set_output_byte(OUTPUT_BYTES_POSITION_REQUEST, position);
6161
communication_.set_output_byte(OUTPUT_BYTES_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-
write_action_bit(kGoToPositionByte, STOP);
68+
communication_.write_action_bit(kGoToPositionByte, STOP);
6969

7070
communication_.read_write_registers();
7171
}
@@ -91,7 +91,6 @@ bool ProtocolLogic::is_stopped(){
9191

9292
bool ProtocolLogic::is_closed(){
9393
return position_ >= kGripperPositionOpenedThreshold;
94-
9594
}
9695

9796
bool ProtocolLogic::is_opened(){
@@ -132,15 +131,4 @@ void ProtocolLogic::refresh_registers(){
132131
position_ = communication_.get_input_byte(INPUT_BYTES_POSITION);
133132
current_ = communication_.get_input_byte(INPUT_BYTES_CURRENT);
134133
}
135-
136-
void ProtocolLogic::write_action_bit(uint8_t position_bit, bool value){
137-
// TODO: change byte from uint to &uint
138-
// byte = bit_set_to(byte, position, value)
139-
communication_.output_registers_[0] = bit_set_to(
140-
communication_.output_registers_[0], 8 + position_bit, value);
141-
}
142-
143-
inline uint ProtocolLogic::bit_set_to(uint number, uint n, bool x) {
144-
return (number & ~((uint)1 << n)) | ((uint)x << n);
145-
}
146134
} // namespace hande_driver

0 commit comments

Comments
 (0)