Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

ci: setup CI using script #29

Merged
merged 19 commits into from
Jul 6, 2023
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Prev Previous commit
Next Next commit
pre-commit run --all-files
Run pre-commit

Signed-off-by: Alex Moriarty <[email protected]>
  • Loading branch information
moriarty committed Jun 27, 2023
commit 7565379d4e02dc1bfd43fba0f10818cc3a84fd0c
Original file line number Diff line number Diff line change
Expand Up @@ -41,20 +41,17 @@ class RobotiqActivationController : public controller_interface::ControllerInter

controller_interface::InterfaceConfiguration state_interface_configuration() const override;

controller_interface::return_type update(
const rclcpp::Time & time,
const rclcpp::Duration & period) override;
controller_interface::return_type update(const rclcpp::Time& time, const rclcpp::Duration& period) override;

CallbackReturn on_activate(const rclcpp_lifecycle::State & previous_state) override;
CallbackReturn on_activate(const rclcpp_lifecycle::State& previous_state) override;

CallbackReturn on_deactivate(const rclcpp_lifecycle::State & previous_state) override;
CallbackReturn on_deactivate(const rclcpp_lifecycle::State& previous_state) override;

CallbackReturn on_init() override;

private:
bool reactivateGripper(
std_srvs::srv::Trigger::Request::SharedPtr req,
std_srvs::srv::Trigger::Response::SharedPtr resp);
bool reactivateGripper(std_srvs::srv::Trigger::Request::SharedPtr req,
std_srvs::srv::Trigger::Response::SharedPtr resp);

static constexpr double ASYNC_WAITING = 2.0;
enum CommandInterfaces
Expand Down
61 changes: 30 additions & 31 deletions robotiq_controllers/src/robotiq_activation_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,7 @@

namespace robotiq_controllers
{
controller_interface::InterfaceConfiguration RobotiqActivationController::
command_interface_configuration() const
controller_interface::InterfaceConfiguration RobotiqActivationController::command_interface_configuration() const
{
controller_interface::InterfaceConfiguration config;
config.type = controller_interface::interface_configuration_type::INDIVIDUAL;
Expand All @@ -42,73 +41,75 @@ command_interface_configuration() const
return config;
}

controller_interface::InterfaceConfiguration RobotiqActivationController::
state_interface_configuration() const
controller_interface::InterfaceConfiguration RobotiqActivationController::state_interface_configuration() const
{
controller_interface::InterfaceConfiguration config;
config.type = controller_interface::interface_configuration_type::INDIVIDUAL;

return config;
}

controller_interface::return_type RobotiqActivationController::update(
const rclcpp::Time & /*time*/,
const rclcpp::Duration & /*period*/)
controller_interface::return_type RobotiqActivationController::update(const rclcpp::Time& /*time*/,
const rclcpp::Duration& /*period*/)
{
return controller_interface::return_type::OK;
}

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
RobotiqActivationController::on_activate(const rclcpp_lifecycle::State & /*previous_state*/)
RobotiqActivationController::on_activate(const rclcpp_lifecycle::State& /*previous_state*/)
{
// Check command interfaces.
if (command_interfaces_.size() != 2) {
RCLCPP_ERROR(
get_node()->get_logger(), "Expected %d command interfaces, but got %zu.", 2,
command_interfaces_.size());
if (command_interfaces_.size() != 2)
{
RCLCPP_ERROR(get_node()->get_logger(), "Expected %d command interfaces, but got %zu.", 2,
command_interfaces_.size());
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
}

try {
try
{
// Create service for re-activating the gripper.
reactivate_gripper_srv_ = get_node()->create_service<std_srvs::srv::Trigger>(
"~/reactivate_gripper",
[this](std_srvs::srv::Trigger::Request::SharedPtr req,
std_srvs::srv::Trigger::Response::SharedPtr resp) {
this->reactivateGripper(req, resp);
});
} catch (...) {
"~/reactivate_gripper",
[this](std_srvs::srv::Trigger::Request::SharedPtr req, std_srvs::srv::Trigger::Response::SharedPtr resp) {
this->reactivateGripper(req, resp);
});
}
catch (...)
{
return LifecycleNodeInterface::CallbackReturn::ERROR;
}
return LifecycleNodeInterface::CallbackReturn::SUCCESS;
}

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
RobotiqActivationController::on_deactivate(const rclcpp_lifecycle::State & /*previous_state*/)
RobotiqActivationController::on_deactivate(const rclcpp_lifecycle::State& /*previous_state*/)
{
try {
try
{
reactivate_gripper_srv_.reset();
} catch (...) {
}
catch (...)
{
return LifecycleNodeInterface::CallbackReturn::ERROR;
}

return LifecycleNodeInterface::CallbackReturn::SUCCESS;
}

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
RobotiqActivationController::on_init()
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn RobotiqActivationController::on_init()
{
return LifecycleNodeInterface::CallbackReturn::SUCCESS;
}

bool RobotiqActivationController::reactivateGripper(
std_srvs::srv::Trigger::Request::SharedPtr /*req*/,
std_srvs::srv::Trigger::Response::SharedPtr resp)
bool RobotiqActivationController::reactivateGripper(std_srvs::srv::Trigger::Request::SharedPtr /*req*/,
std_srvs::srv::Trigger::Response::SharedPtr resp)
{
command_interfaces_[REACTIVATE_GRIPPER_RESPONSE].set_value(ASYNC_WAITING);
command_interfaces_[REACTIVATE_GRIPPER_CMD].set_value(1.0);

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

#include "pluginlib/class_list_macros.hpp"

PLUGINLIB_EXPORT_CLASS(
robotiq_controllers::RobotiqActivationController,
controller_interface::ControllerInterface)
PLUGINLIB_EXPORT_CLASS(robotiq_controllers::RobotiqActivationController, controller_interface::ControllerInterface)
2 changes: 1 addition & 1 deletion robotiq_driver/include/robotiq_driver/crc.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,4 +3,4 @@
#include <vector>
#include <cstdint>

uint16_t computeCRC(const std::vector<uint8_t> & cmd);
uint16_t computeCRC(const std::vector<uint8_t>& cmd);
14 changes: 5 additions & 9 deletions robotiq_driver/include/robotiq_driver/hardware_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ class RobotiqGripperHardwareInterface : public hardware_interface::SystemInterfa
RobotiqGripperHardwareInterface();

ROBOTIQ_DRIVER_PUBLIC
CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override;
CallbackReturn on_init(const hardware_interface::HardwareInfo& info) override;

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

ROBOTIQ_DRIVER_PUBLIC
CallbackReturn on_activate(const rclcpp_lifecycle::State & previous_state) override;
CallbackReturn on_activate(const rclcpp_lifecycle::State& previous_state) override;

ROBOTIQ_DRIVER_PUBLIC
CallbackReturn on_deactivate(const rclcpp_lifecycle::State & previous_state) override;
CallbackReturn on_deactivate(const rclcpp_lifecycle::State& previous_state) override;

ROBOTIQ_DRIVER_PUBLIC
hardware_interface::return_type read(
const rclcpp::Time & time,
const rclcpp::Duration & period) override;
hardware_interface::return_type read(const rclcpp::Time& time, const rclcpp::Duration& period) override;

ROBOTIQ_DRIVER_PUBLIC
hardware_interface::return_type write(
const rclcpp::Time & time,
const rclcpp::Duration & period) override;
hardware_interface::return_type write(const rclcpp::Time& time, const rclcpp::Duration& period) override;

private:
static constexpr double NO_NEW_CMD_ = std::numeric_limits<double>::quiet_NaN();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@
class RobotiqGripperInterface
{
public:
RobotiqGripperInterface(const std::string & com_port = "/dev/ttyUSB0", uint8_t slave_id = 0x09);
RobotiqGripperInterface(const std::string& com_port = "/dev/ttyUSB0", uint8_t slave_id = 0x09);

/**
* @brief Activates the gripper.
Expand Down Expand Up @@ -122,9 +122,7 @@ class RobotiqGripperInterface

private:
std::vector<uint8_t> createReadCommand(uint16_t first_register, uint8_t num_registers);
std::vector<uint8_t> createWriteCommand(
uint16_t first_register,
const std::vector<uint16_t> & data);
std::vector<uint8_t> createWriteCommand(uint16_t first_register, const std::vector<uint16_t>& data);

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

/**
* @brief Read the current status of the gripper, and update member variables as appropriate.
Expand Down
83 changes: 29 additions & 54 deletions robotiq_driver/src/crc.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,72 +2,47 @@

/* Table of CRC values for high–order byte */
static unsigned char kCRCHiTable[] = {
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40,
0x01, 0xC0, 0x80,
0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80,
0x41, 0x00, 0xC1,
0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0,
0x80, 0x41, 0x01,
0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00,
0xC1, 0x81, 0x40,
0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81,
0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81,
0x40, 0x01, 0xC0,
0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0,
0x80, 0x41, 0x00,
0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01,
0xC0, 0x80, 0x41,
0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
0x01, 0xC0, 0x80,
0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81,
0x40, 0x01, 0xC0,
0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1,
0x81, 0x40, 0x01,
0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01,
0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40,
0x01, 0xC0, 0x80,
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80,
0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1,
0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01,
0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40,
0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81,
0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0,
0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00,
0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80,
0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0,
0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01,
0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80,
0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40
};

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

uint16_t computeCRC(const std::vector<uint8_t> & cmd)
uint16_t computeCRC(const std::vector<uint8_t>& cmd)
{
uint16_t crc_hi = 0x00FF;
uint16_t crc_lo = 0x00FF;

for (auto byte : cmd) {
for (auto byte : cmd)
{
std::size_t index = crc_lo ^ byte;
crc_lo = crc_hi ^ kCRCHiTable[index];
crc_hi = kCRCLoTable[index];
Expand Down
25 changes: 17 additions & 8 deletions robotiq_driver/src/gripper_interface_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,8 @@ constexpr auto kSlaveID = 0x09;

int main()
{
try {
try
{
RobotiqGripperInterface gripper(kComPort, kSlaveID);

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

std::cout << "Closing gripper...\n";
gripper.setGripperPosition(0xFF);
while (gripper.gripperIsMoving()) {
while (gripper.gripperIsMoving())
{
std::this_thread::sleep_for(std::chrono::milliseconds(500));
}

std::cout << "Opening gripper...\n";
gripper.setGripperPosition(0x00);
while (gripper.gripperIsMoving()) {
while (gripper.gripperIsMoving())
{
std::this_thread::sleep_for(std::chrono::milliseconds(500));
}

std::cout << "Half closing gripper...\n";
gripper.setGripperPosition(0x80);
while (gripper.gripperIsMoving()) {
while (gripper.gripperIsMoving())
{
std::this_thread::sleep_for(std::chrono::milliseconds(500));
}

std::cout << "Opening gripper...\n";
gripper.setGripperPosition(0x00);
while (gripper.gripperIsMoving()) {
while (gripper.gripperIsMoving())
{
std::this_thread::sleep_for(std::chrono::milliseconds(500));
}

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

std::cout << "Closing gripper...\n";
gripper.setGripperPosition(0xFF);
while (gripper.gripperIsMoving()) {
while (gripper.gripperIsMoving())
{
std::this_thread::sleep_for(std::chrono::milliseconds(500));
}

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

std::cout << "Opening gripper...\n";
gripper.setGripperPosition(0x00);
while (gripper.gripperIsMoving()) {
while (gripper.gripperIsMoving())
{
std::this_thread::sleep_for(std::chrono::milliseconds(500));
}
} catch (const serial::IOException & e) {
}
catch (const serial::IOException& e)
{
std::cout << "Failed to communicating with the Gripper. Please check the Gripper connection";
return 1;
}
Expand Down
Loading