Skip to content

Commit 7565379

Browse files
committed
pre-commit run --all-files
Run pre-commit Signed-off-by: Alex Moriarty <[email protected]>
1 parent 1d95302 commit 7565379

File tree

9 files changed

+266
-276
lines changed

9 files changed

+266
-276
lines changed

robotiq_controllers/include/robotiq_controllers/robotiq_activation_controller.hpp

Lines changed: 5 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -41,20 +41,17 @@ class RobotiqActivationController : public controller_interface::ControllerInter
4141

4242
controller_interface::InterfaceConfiguration state_interface_configuration() const override;
4343

44-
controller_interface::return_type update(
45-
const rclcpp::Time & time,
46-
const rclcpp::Duration & period) override;
44+
controller_interface::return_type update(const rclcpp::Time& time, const rclcpp::Duration& period) override;
4745

48-
CallbackReturn on_activate(const rclcpp_lifecycle::State & previous_state) override;
46+
CallbackReturn on_activate(const rclcpp_lifecycle::State& previous_state) override;
4947

50-
CallbackReturn on_deactivate(const rclcpp_lifecycle::State & previous_state) override;
48+
CallbackReturn on_deactivate(const rclcpp_lifecycle::State& previous_state) override;
5149

5250
CallbackReturn on_init() override;
5351

5452
private:
55-
bool reactivateGripper(
56-
std_srvs::srv::Trigger::Request::SharedPtr req,
57-
std_srvs::srv::Trigger::Response::SharedPtr resp);
53+
bool reactivateGripper(std_srvs::srv::Trigger::Request::SharedPtr req,
54+
std_srvs::srv::Trigger::Response::SharedPtr resp);
5855

5956
static constexpr double ASYNC_WAITING = 2.0;
6057
enum CommandInterfaces

robotiq_controllers/src/robotiq_activation_controller.cpp

Lines changed: 30 additions & 31 deletions
Original file line numberDiff line numberDiff line change
@@ -30,8 +30,7 @@
3030

3131
namespace robotiq_controllers
3232
{
33-
controller_interface::InterfaceConfiguration RobotiqActivationController::
34-
command_interface_configuration() const
33+
controller_interface::InterfaceConfiguration RobotiqActivationController::command_interface_configuration() const
3534
{
3635
controller_interface::InterfaceConfiguration config;
3736
config.type = controller_interface::interface_configuration_type::INDIVIDUAL;
@@ -42,73 +41,75 @@ command_interface_configuration() const
4241
return config;
4342
}
4443

45-
controller_interface::InterfaceConfiguration RobotiqActivationController::
46-
state_interface_configuration() const
44+
controller_interface::InterfaceConfiguration RobotiqActivationController::state_interface_configuration() const
4745
{
4846
controller_interface::InterfaceConfiguration config;
4947
config.type = controller_interface::interface_configuration_type::INDIVIDUAL;
5048

5149
return config;
5250
}
5351

54-
controller_interface::return_type RobotiqActivationController::update(
55-
const rclcpp::Time & /*time*/,
56-
const rclcpp::Duration & /*period*/)
52+
controller_interface::return_type RobotiqActivationController::update(const rclcpp::Time& /*time*/,
53+
const rclcpp::Duration& /*period*/)
5754
{
5855
return controller_interface::return_type::OK;
5956
}
6057

6158
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
62-
RobotiqActivationController::on_activate(const rclcpp_lifecycle::State & /*previous_state*/)
59+
RobotiqActivationController::on_activate(const rclcpp_lifecycle::State& /*previous_state*/)
6360
{
6461
// Check command interfaces.
65-
if (command_interfaces_.size() != 2) {
66-
RCLCPP_ERROR(
67-
get_node()->get_logger(), "Expected %d command interfaces, but got %zu.", 2,
68-
command_interfaces_.size());
62+
if (command_interfaces_.size() != 2)
63+
{
64+
RCLCPP_ERROR(get_node()->get_logger(), "Expected %d command interfaces, but got %zu.", 2,
65+
command_interfaces_.size());
6966
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
7067
}
7168

72-
try {
69+
try
70+
{
7371
// Create service for re-activating the gripper.
7472
reactivate_gripper_srv_ = get_node()->create_service<std_srvs::srv::Trigger>(
75-
"~/reactivate_gripper",
76-
[this](std_srvs::srv::Trigger::Request::SharedPtr req,
77-
std_srvs::srv::Trigger::Response::SharedPtr resp) {
78-
this->reactivateGripper(req, resp);
79-
});
80-
} catch (...) {
73+
"~/reactivate_gripper",
74+
[this](std_srvs::srv::Trigger::Request::SharedPtr req, std_srvs::srv::Trigger::Response::SharedPtr resp) {
75+
this->reactivateGripper(req, resp);
76+
});
77+
}
78+
catch (...)
79+
{
8180
return LifecycleNodeInterface::CallbackReturn::ERROR;
8281
}
8382
return LifecycleNodeInterface::CallbackReturn::SUCCESS;
8483
}
8584

8685
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
87-
RobotiqActivationController::on_deactivate(const rclcpp_lifecycle::State & /*previous_state*/)
86+
RobotiqActivationController::on_deactivate(const rclcpp_lifecycle::State& /*previous_state*/)
8887
{
89-
try {
88+
try
89+
{
9090
reactivate_gripper_srv_.reset();
91-
} catch (...) {
91+
}
92+
catch (...)
93+
{
9294
return LifecycleNodeInterface::CallbackReturn::ERROR;
9395
}
9496

9597
return LifecycleNodeInterface::CallbackReturn::SUCCESS;
9698
}
9799

98-
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
99-
RobotiqActivationController::on_init()
100+
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn RobotiqActivationController::on_init()
100101
{
101102
return LifecycleNodeInterface::CallbackReturn::SUCCESS;
102103
}
103104

104-
bool RobotiqActivationController::reactivateGripper(
105-
std_srvs::srv::Trigger::Request::SharedPtr /*req*/,
106-
std_srvs::srv::Trigger::Response::SharedPtr resp)
105+
bool RobotiqActivationController::reactivateGripper(std_srvs::srv::Trigger::Request::SharedPtr /*req*/,
106+
std_srvs::srv::Trigger::Response::SharedPtr resp)
107107
{
108108
command_interfaces_[REACTIVATE_GRIPPER_RESPONSE].set_value(ASYNC_WAITING);
109109
command_interfaces_[REACTIVATE_GRIPPER_CMD].set_value(1.0);
110110

111-
while (command_interfaces_[REACTIVATE_GRIPPER_RESPONSE].get_value() == ASYNC_WAITING) {
111+
while (command_interfaces_[REACTIVATE_GRIPPER_RESPONSE].get_value() == ASYNC_WAITING)
112+
{
112113
std::this_thread::sleep_for(std::chrono::milliseconds(50));
113114
}
114115
resp->success = command_interfaces_[REACTIVATE_GRIPPER_RESPONSE].get_value();
@@ -119,6 +120,4 @@ bool RobotiqActivationController::reactivateGripper(
119120

120121
#include "pluginlib/class_list_macros.hpp"
121122

122-
PLUGINLIB_EXPORT_CLASS(
123-
robotiq_controllers::RobotiqActivationController,
124-
controller_interface::ControllerInterface)
123+
PLUGINLIB_EXPORT_CLASS(robotiq_controllers::RobotiqActivationController, controller_interface::ControllerInterface)

robotiq_driver/include/robotiq_driver/crc.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,4 +3,4 @@
33
#include <vector>
44
#include <cstdint>
55

6-
uint16_t computeCRC(const std::vector<uint8_t> & cmd);
6+
uint16_t computeCRC(const std::vector<uint8_t>& cmd);

robotiq_driver/include/robotiq_driver/hardware_interface.hpp

Lines changed: 5 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,7 @@ class RobotiqGripperHardwareInterface : public hardware_interface::SystemInterfa
5454
RobotiqGripperHardwareInterface();
5555

5656
ROBOTIQ_DRIVER_PUBLIC
57-
CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override;
57+
CallbackReturn on_init(const hardware_interface::HardwareInfo& info) override;
5858

5959
ROBOTIQ_DRIVER_PUBLIC
6060
std::vector<hardware_interface::StateInterface> export_state_interfaces() override;
@@ -63,20 +63,16 @@ class RobotiqGripperHardwareInterface : public hardware_interface::SystemInterfa
6363
std::vector<hardware_interface::CommandInterface> export_command_interfaces() override;
6464

6565
ROBOTIQ_DRIVER_PUBLIC
66-
CallbackReturn on_activate(const rclcpp_lifecycle::State & previous_state) override;
66+
CallbackReturn on_activate(const rclcpp_lifecycle::State& previous_state) override;
6767

6868
ROBOTIQ_DRIVER_PUBLIC
69-
CallbackReturn on_deactivate(const rclcpp_lifecycle::State & previous_state) override;
69+
CallbackReturn on_deactivate(const rclcpp_lifecycle::State& previous_state) override;
7070

7171
ROBOTIQ_DRIVER_PUBLIC
72-
hardware_interface::return_type read(
73-
const rclcpp::Time & time,
74-
const rclcpp::Duration & period) override;
72+
hardware_interface::return_type read(const rclcpp::Time& time, const rclcpp::Duration& period) override;
7573

7674
ROBOTIQ_DRIVER_PUBLIC
77-
hardware_interface::return_type write(
78-
const rclcpp::Time & time,
79-
const rclcpp::Duration & period) override;
75+
hardware_interface::return_type write(const rclcpp::Time& time, const rclcpp::Duration& period) override;
8076

8177
private:
8278
static constexpr double NO_NEW_CMD_ = std::numeric_limits<double>::quiet_NaN();

robotiq_driver/include/robotiq_driver/robotiq_gripper_interface.hpp

Lines changed: 3 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@
4141
class RobotiqGripperInterface
4242
{
4343
public:
44-
RobotiqGripperInterface(const std::string & com_port = "/dev/ttyUSB0", uint8_t slave_id = 0x09);
44+
RobotiqGripperInterface(const std::string& com_port = "/dev/ttyUSB0", uint8_t slave_id = 0x09);
4545

4646
/**
4747
* @brief Activates the gripper.
@@ -122,9 +122,7 @@ class RobotiqGripperInterface
122122

123123
private:
124124
std::vector<uint8_t> createReadCommand(uint16_t first_register, uint8_t num_registers);
125-
std::vector<uint8_t> createWriteCommand(
126-
uint16_t first_register,
127-
const std::vector<uint16_t> & data);
125+
std::vector<uint8_t> createWriteCommand(uint16_t first_register, const std::vector<uint16_t>& data);
128126

129127
/**
130128
* @brief read response from the gripper.
@@ -140,7 +138,7 @@ class RobotiqGripperInterface
140138
* @param cmd The command.
141139
* @throw serial::IOException on failure to successfully communicate with gripper port
142140
*/
143-
void sendCommand(const std::vector<uint8_t> & cmd);
141+
void sendCommand(const std::vector<uint8_t>& cmd);
144142

145143
/**
146144
* @brief Read the current status of the gripper, and update member variables as appropriate.

robotiq_driver/src/crc.cpp

Lines changed: 29 additions & 54 deletions
Original file line numberDiff line numberDiff line change
@@ -2,72 +2,47 @@
22

33
/* Table of CRC values for high–order byte */
44
static unsigned char kCRCHiTable[] = {
5-
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40,
6-
0x01, 0xC0, 0x80,
7-
0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80,
8-
0x41, 0x00, 0xC1,
9-
0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0,
10-
0x80, 0x41, 0x01,
11-
0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00,
12-
0xC1, 0x81, 0x40,
13-
0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
14-
0x00, 0xC1, 0x81,
15-
0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81,
16-
0x40, 0x01, 0xC0,
17-
0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0,
18-
0x80, 0x41, 0x00,
19-
0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01,
20-
0xC0, 0x80, 0x41,
21-
0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
22-
0x01, 0xC0, 0x80,
23-
0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81,
24-
0x40, 0x01, 0xC0,
25-
0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1,
26-
0x81, 0x40, 0x01,
27-
0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01,
28-
0xC0, 0x80, 0x41,
29-
0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40,
30-
0x01, 0xC0, 0x80,
5+
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80,
6+
0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1,
7+
0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01,
8+
0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40,
9+
0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81,
10+
0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0,
11+
0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00,
12+
0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
13+
0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80,
14+
0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0,
15+
0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01,
16+
0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
17+
0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80,
3118
0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40
3219
};
3320

3421
/* Table of CRC values for low–order byte */
3522
static unsigned char kCRCLoTable[] = {
36-
0x00, 0xC0, 0xC1, 0x01, 0xC3, 0x03, 0x02, 0xC2, 0xC6, 0x06, 0x07, 0xC7, 0x05, 0xC5, 0xC4, 0x04,
37-
0xCC, 0x0C, 0x0D,
38-
0xCD, 0x0F, 0xCF, 0xCE, 0x0E, 0x0A, 0xCA, 0xCB, 0x0B, 0xC9, 0x09, 0x08, 0xC8, 0xD8, 0x18, 0x19,
39-
0xD9, 0x1B, 0xDB,
40-
0xDA, 0x1A, 0x1E, 0xDE, 0xDF, 0x1F, 0xDD, 0x1D, 0x1C, 0xDC, 0x14, 0xD4, 0xD5, 0x15, 0xD7, 0x17,
41-
0x16, 0xD6, 0xD2,
42-
0x12, 0x13, 0xD3, 0x11, 0xD1, 0xD0, 0x10, 0xF0, 0x30, 0x31, 0xF1, 0x33, 0xF3, 0xF2, 0x32, 0x36,
43-
0xF6, 0xF7, 0x37,
44-
0xF5, 0x35, 0x34, 0xF4, 0x3C, 0xFC, 0xFD, 0x3D, 0xFF, 0x3F, 0x3E, 0xFE, 0xFA, 0x3A, 0x3B, 0xFB,
45-
0x39, 0xF9, 0xF8,
46-
0x38, 0x28, 0xE8, 0xE9, 0x29, 0xEB, 0x2B, 0x2A, 0xEA, 0xEE, 0x2E, 0x2F, 0xEF, 0x2D, 0xED, 0xEC,
47-
0x2C, 0xE4, 0x24,
48-
0x25, 0xE5, 0x27, 0xE7, 0xE6, 0x26, 0x22, 0xE2, 0xE3, 0x23, 0xE1, 0x21, 0x20, 0xE0, 0xA0, 0x60,
49-
0x61, 0xA1, 0x63,
50-
0xA3, 0xA2, 0x62, 0x66, 0xA6, 0xA7, 0x67, 0xA5, 0x65, 0x64, 0xA4, 0x6C, 0xAC, 0xAD, 0x6D, 0xAF,
51-
0x6F, 0x6E, 0xAE,
52-
0xAA, 0x6A, 0x6B, 0xAB, 0x69, 0xA9, 0xA8, 0x68, 0x78, 0xB8, 0xB9, 0x79, 0xBB, 0x7B, 0x7A, 0xBA,
53-
0xBE, 0x7E, 0x7F,
54-
0xBF, 0x7D, 0xBD, 0xBC, 0x7C, 0xB4, 0x74, 0x75, 0xB5, 0x77, 0xB7, 0xB6, 0x76, 0x72, 0xB2, 0xB3,
55-
0x73, 0xB1, 0x71,
56-
0x70, 0xB0, 0x50, 0x90, 0x91, 0x51, 0x93, 0x53, 0x52, 0x92, 0x96, 0x56, 0x57, 0x97, 0x55, 0x95,
57-
0x94, 0x54, 0x9C,
58-
0x5C, 0x5D, 0x9D, 0x5F, 0x9F, 0x9E, 0x5E, 0x5A, 0x9A, 0x9B, 0x5B, 0x99, 0x59, 0x58, 0x98, 0x88,
59-
0x48, 0x49, 0x89,
60-
0x4B, 0x8B, 0x8A, 0x4A, 0x4E, 0x8E, 0x8F, 0x4F, 0x8D, 0x4D, 0x4C, 0x8C, 0x44, 0x84, 0x85, 0x45,
61-
0x87, 0x47, 0x46,
23+
0x00, 0xC0, 0xC1, 0x01, 0xC3, 0x03, 0x02, 0xC2, 0xC6, 0x06, 0x07, 0xC7, 0x05, 0xC5, 0xC4, 0x04, 0xCC, 0x0C, 0x0D,
24+
0xCD, 0x0F, 0xCF, 0xCE, 0x0E, 0x0A, 0xCA, 0xCB, 0x0B, 0xC9, 0x09, 0x08, 0xC8, 0xD8, 0x18, 0x19, 0xD9, 0x1B, 0xDB,
25+
0xDA, 0x1A, 0x1E, 0xDE, 0xDF, 0x1F, 0xDD, 0x1D, 0x1C, 0xDC, 0x14, 0xD4, 0xD5, 0x15, 0xD7, 0x17, 0x16, 0xD6, 0xD2,
26+
0x12, 0x13, 0xD3, 0x11, 0xD1, 0xD0, 0x10, 0xF0, 0x30, 0x31, 0xF1, 0x33, 0xF3, 0xF2, 0x32, 0x36, 0xF6, 0xF7, 0x37,
27+
0xF5, 0x35, 0x34, 0xF4, 0x3C, 0xFC, 0xFD, 0x3D, 0xFF, 0x3F, 0x3E, 0xFE, 0xFA, 0x3A, 0x3B, 0xFB, 0x39, 0xF9, 0xF8,
28+
0x38, 0x28, 0xE8, 0xE9, 0x29, 0xEB, 0x2B, 0x2A, 0xEA, 0xEE, 0x2E, 0x2F, 0xEF, 0x2D, 0xED, 0xEC, 0x2C, 0xE4, 0x24,
29+
0x25, 0xE5, 0x27, 0xE7, 0xE6, 0x26, 0x22, 0xE2, 0xE3, 0x23, 0xE1, 0x21, 0x20, 0xE0, 0xA0, 0x60, 0x61, 0xA1, 0x63,
30+
0xA3, 0xA2, 0x62, 0x66, 0xA6, 0xA7, 0x67, 0xA5, 0x65, 0x64, 0xA4, 0x6C, 0xAC, 0xAD, 0x6D, 0xAF, 0x6F, 0x6E, 0xAE,
31+
0xAA, 0x6A, 0x6B, 0xAB, 0x69, 0xA9, 0xA8, 0x68, 0x78, 0xB8, 0xB9, 0x79, 0xBB, 0x7B, 0x7A, 0xBA, 0xBE, 0x7E, 0x7F,
32+
0xBF, 0x7D, 0xBD, 0xBC, 0x7C, 0xB4, 0x74, 0x75, 0xB5, 0x77, 0xB7, 0xB6, 0x76, 0x72, 0xB2, 0xB3, 0x73, 0xB1, 0x71,
33+
0x70, 0xB0, 0x50, 0x90, 0x91, 0x51, 0x93, 0x53, 0x52, 0x92, 0x96, 0x56, 0x57, 0x97, 0x55, 0x95, 0x94, 0x54, 0x9C,
34+
0x5C, 0x5D, 0x9D, 0x5F, 0x9F, 0x9E, 0x5E, 0x5A, 0x9A, 0x9B, 0x5B, 0x99, 0x59, 0x58, 0x98, 0x88, 0x48, 0x49, 0x89,
35+
0x4B, 0x8B, 0x8A, 0x4A, 0x4E, 0x8E, 0x8F, 0x4F, 0x8D, 0x4D, 0x4C, 0x8C, 0x44, 0x84, 0x85, 0x45, 0x87, 0x47, 0x46,
6236
0x86, 0x82, 0x42, 0x43, 0x83, 0x41, 0x81, 0x80, 0x40
6337
};
6438

65-
uint16_t computeCRC(const std::vector<uint8_t> & cmd)
39+
uint16_t computeCRC(const std::vector<uint8_t>& cmd)
6640
{
6741
uint16_t crc_hi = 0x00FF;
6842
uint16_t crc_lo = 0x00FF;
6943

70-
for (auto byte : cmd) {
44+
for (auto byte : cmd)
45+
{
7146
std::size_t index = crc_lo ^ byte;
7247
crc_lo = crc_hi ^ kCRCHiTable[index];
7348
crc_hi = kCRCLoTable[index];

robotiq_driver/src/gripper_interface_test.cpp

Lines changed: 17 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,8 @@ constexpr auto kSlaveID = 0x09;
3636

3737
int main()
3838
{
39-
try {
39+
try
40+
{
4041
RobotiqGripperInterface gripper(kComPort, kSlaveID);
4142

4243
std::cout << "Deactivating gripper...\n";
@@ -49,25 +50,29 @@ int main()
4950

5051
std::cout << "Closing gripper...\n";
5152
gripper.setGripperPosition(0xFF);
52-
while (gripper.gripperIsMoving()) {
53+
while (gripper.gripperIsMoving())
54+
{
5355
std::this_thread::sleep_for(std::chrono::milliseconds(500));
5456
}
5557

5658
std::cout << "Opening gripper...\n";
5759
gripper.setGripperPosition(0x00);
58-
while (gripper.gripperIsMoving()) {
60+
while (gripper.gripperIsMoving())
61+
{
5962
std::this_thread::sleep_for(std::chrono::milliseconds(500));
6063
}
6164

6265
std::cout << "Half closing gripper...\n";
6366
gripper.setGripperPosition(0x80);
64-
while (gripper.gripperIsMoving()) {
67+
while (gripper.gripperIsMoving())
68+
{
6569
std::this_thread::sleep_for(std::chrono::milliseconds(500));
6670
}
6771

6872
std::cout << "Opening gripper...\n";
6973
gripper.setGripperPosition(0x00);
70-
while (gripper.gripperIsMoving()) {
74+
while (gripper.gripperIsMoving())
75+
{
7176
std::this_thread::sleep_for(std::chrono::milliseconds(500));
7277
}
7378

@@ -76,7 +81,8 @@ int main()
7681

7782
std::cout << "Closing gripper...\n";
7883
gripper.setGripperPosition(0xFF);
79-
while (gripper.gripperIsMoving()) {
84+
while (gripper.gripperIsMoving())
85+
{
8086
std::this_thread::sleep_for(std::chrono::milliseconds(500));
8187
}
8288

@@ -85,10 +91,13 @@ int main()
8591

8692
std::cout << "Opening gripper...\n";
8793
gripper.setGripperPosition(0x00);
88-
while (gripper.gripperIsMoving()) {
94+
while (gripper.gripperIsMoving())
95+
{
8996
std::this_thread::sleep_for(std::chrono::milliseconds(500));
9097
}
91-
} catch (const serial::IOException & e) {
98+
}
99+
catch (const serial::IOException& e)
100+
{
92101
std::cout << "Failed to communicating with the Gripper. Please check the Gripper connection";
93102
return 1;
94103
}

0 commit comments

Comments
 (0)