Skip to content

Commit

Permalink
- removed visibility macros and used solution S1 for visibility macros
Browse files Browse the repository at this point in the history
- removed the template from license
- added one variable per line
- documented the enums
- updated the doc folder as per `joint_trajectory_controller`
  • Loading branch information
sachinkum0009 committed Jan 2, 2025
1 parent e079889 commit 4640609
Show file tree
Hide file tree
Showing 13 changed files with 174 additions and 67 deletions.
4 changes: 4 additions & 0 deletions io_gripper_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,10 @@ if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Werror=conversion -Werror=unused-but-set-variable -Werror=return-type -Werror=shadow)
endif()

# using this instead of visibility macros
# S1 from https://github.com/ros-controls/ros2_controllers/issues/1053
set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON)

# find dependencies
set(THIS_PACKAGE_INCLUDE_DEPENDS
sensor_msgs
Expand Down
10 changes: 3 additions & 7 deletions io_gripper_controller/README.md
Original file line number Diff line number Diff line change
@@ -1,9 +1,5 @@
# IO Gripper Controller
# io_gripper_controller package

The IO Gripper Controller is provides implementation to control the gripper using IOs. It provides functionalities like open, close and reconfigure which can be used either though action server or service server and also publishes `joint_states` of gripper and also `dynamic_interfaces` for all command and state interfaces.

## Description of controller's interfaces

- `joint_states` [`sensor_msgs::msg::JointState`]: Publishes the state of gripper joint and configuration joint
- `dynamic_interfaces` [`control_msgs::msg::DynamicInterfaceValues`]: Publishes all command and state interface of the IOs and sensors of gripper.
The package implements controllers to control the gripper using IOs.

For detailed documentation check the `docs` folder or [ros2_control documentation](https://control.ros.org/).
99 changes: 99 additions & 0 deletions io_gripper_controller/doc/userdoc.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
:github_url: https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/io_gripper_controller/doc/userdoc.rst

.. _io_gripper_controller_userdoc:

io_gripper_controller
=============================

The IO Gripper Controller provides implementation to control the gripper using IOs. It provides functionalities like open, close and reconfigure which can be used either though action server or service server and also publishes `joint_states` of gripper and also `dynamic_interfaces` for all command and state interfaces.

Description of controller's interfaces
---------------------------------------

- `joint_states` [`sensor_msgs::msg::JointState`]: Publishes the state of gripper joint and configuration joint
- `dynamic_interfaces` [`control_msgs::msg::DynamicInterfaceValues`]: Publishes all command and state interface of the IOs and sensors of gripper.


Parameters
,,,,,,,,,,,

This controller uses the `generate_parameter_library <https://github.com/PickNikRobotics/generate_parameter_library>`_ to handle its parameters.

This controller adds the following parameters:

.. generate_parameter_library_details:: ../src/io_gripper_controller.yaml


Example parameters
....................

```
io_gripper_controller:

ros__parameters:

use_action: true

open_close_joints: [gripper_clamp_jaw]

open:
joint_states: [0.0]
set_before_command:
high: [EL2008/Bremse_WQG7]
low: []
command:
high: [EL2008/Greiferteil_Oeffnen_WQG1]
low: [EL2008/Greiferteil_Schliessen_WQG2]
state:
high: [EL1008/Greifer_Geoeffnet_BG01]
low: [EL1008/Greifer_Geschloschen_BG02]
set_after_command:
high: []
low: [EL2008/Bremse_WQG7]

possible_closed_states: ['empty_close', 'full_close']

close:
set_before_command:
high: [EL2008/Bremse_WQG7]
low: [EL2008/Greiferteil_Oeffnen_WQG1]
command:
high: [EL2008/Greiferteil_Schliessen_WQG2]
low: [EL2008/Greiferteil_Oeffnen_WQG1]
state:
empty_close:
joint_states: [0.08]
high: [EL1008/Greifer_Geschloschen_BG02]
low: [EL1008/Bauteilabfrage_BG06]
set_after_command_high: [EL2008/Bremse_WQG7]
set_after_command_low: [EL2008/Bremse_WQG7]
full_close:
joint_states: [0.08]
high: [EL1008/Bauteilabfrage_BG06]
low: [EL1008/Greifer_Geschloschen_BG02]
set_after_command_high: [EL2008/Bremse_WQG7]
set_after_command_low: [EL2008/Bremse_WQG7]

configurations: ["stichmass_125", "stichmass_250"]
configuration_joints: [gripper_gripper_distance_joint]

configuration_setup:
stichmass_125:
joint_states: [0.125]
command_high: [EL2008/Stichmass_125_WQG5]
command_low: [EL2008/Stichmass_250_WQG6]
state_high: [EL1008/Stichmass_125mm_BG03]
state_low: [EL1008/Stichmass_250mm_BG04]
stichmass_250:
joint_states: [0.250]
command_high: [EL2008/Stichmass_250_WQG6]
command_low: [EL2008/Stichmass_125_WQG5]
state_high: [EL1008/Stichmass_250mm_BG04]
state_low: [EL1008/Stichmass_125mm_BG03]

gripper_specific_sensors: ["hohenabfrage", "bauteilabfrage"]
sensors_interfaces:
hohenabfrage:
input: "EL1008/Hohenabfrage_BG5"
bauteilabfrage:
input: "EL1008/Bauteilabfrage_BG06"
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright (c) 2024, Stogl Robotics Consulting UG (haftungsbeschränkt) (template)
// Copyright (c) 2024, Stogl Robotics Consulting UG (haftungsbeschränkt)
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -12,11 +12,6 @@
// See the License for the specific language governing permissions and
// limitations under the License.

//
// Source of this file are templates in
// [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository.
//

#ifndef GRIPPER_IO_CONTROLLER__GRIPPER_IO_CONTROLLER_HPP_
#define GRIPPER_IO_CONTROLLER__GRIPPER_IO_CONTROLLER_HPP_

Expand All @@ -29,7 +24,6 @@

#include "controller_interface/controller_interface.hpp"
#include "io_gripper_controller_parameters.hpp"
#include "io_gripper_controller/visibility_control.h"
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
#include "rclcpp_lifecycle/state.hpp"
#include "realtime_tools/realtime_buffer.h"
Expand All @@ -50,25 +44,53 @@
namespace io_gripper_controller
{

/**
* @enum service_mode_type
* @brief Represents the various service modes of the gripper. These modes represents the high level states of the gripper.
*
* - IDLE: The gripper is in an idle state, not performing any action.
* - OPEN: The gripper is in the process of opening.
* - CLOSE: The gripper is in the process of closing.
*/
enum class service_mode_type : std::uint8_t
{
IDLE = 0,
OPEN = 1,
CLOSE = 2,
};

/**
* @enum gripper_state_type
* @brief Represents the various states of the gripper.
*
* - IDLE: The gripper is in an idle state, not performing any action.
* - SET_BEFORE_COMMAND: Executing commands for io defined in the yaml which are required before opening the gripper.
* - CLOSE_GRIPPER: Executing commands to close the gripper.
* - CHECK_GRIPPER_STATE: Checking the state of the gripper to make sure the gripper is closed.
* - OPEN_GRIPPER: Executing commands to open the gripper.
* - SET_AFTER_COMMAND: Setting the gripper state after executing a command.
* - HALTED: The gripper operation is halted.
*/
enum class gripper_state_type : std::uint8_t
{
IDLE = 0,
SET_BEFORE_COMMAND = 1,
CLOSE_GRIPPER = 2,
CHECK_GRIPPER_STATE = 3,
OPEN_GRIPPER = 4,
START_CLOSE_GRIPPER = 5,
SET_AFTER_COMMAND = 6,
HALTED = 7,
SET_AFTER_COMMAND = 5,
HALTED = 6,
};

/**
* @enum reconfigure_state_type
* @brief Represents the various states of the reconfiguration process, which means that the gripper is reconfiguring to new state based on the configuration defined in the yaml params.
*
* - IDLE: The reconfiguration process is idle, not performing any action.
* - FIND_CONFIG: Finding the configuration settings.
* - SET_COMMAND: Setting the command based on the configuration.
* - CHECK_STATE: Checking the state after setting the command.
*/
enum class reconfigure_state_type : std::uint8_t
{
IDLE = 0,
Expand All @@ -80,51 +102,56 @@ enum class reconfigure_state_type : std::uint8_t
class IOGripperController : public controller_interface::ControllerInterface
{
public:
GRIPPER_IO_CONTROLLER__VISIBILITY_PUBLIC
IOGripperController();
io_gripper_controller::Params params_;

GRIPPER_IO_CONTROLLER__VISIBILITY_PUBLIC
controller_interface::CallbackReturn on_init() override;

GRIPPER_IO_CONTROLLER__VISIBILITY_PUBLIC
controller_interface::InterfaceConfiguration command_interface_configuration() const override;

GRIPPER_IO_CONTROLLER__VISIBILITY_PUBLIC
controller_interface::InterfaceConfiguration state_interface_configuration() const override;

GRIPPER_IO_CONTROLLER__VISIBILITY_PUBLIC
controller_interface::CallbackReturn on_configure(
const rclcpp_lifecycle::State & previous_state) override;

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

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

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

std::vector<std::string> command_ios_open, command_ios_close, set_before_command_open, set_after_command_open, reconfigure_command;
std::vector<double> command_ios_open_values, command_ios_close_values, set_before_command_open_values, set_after_command_open_values, reconfigure_command_values;
std::vector<std::string> state_ios_open, state_ios_close, set_before_command_close, set_after_command_close;
std::vector<double> state_ios_open_values, state_ios_close_values, set_before_command_close_values, set_after_command_close_values, set_after_command_open_values_original_;
std::vector<std::string> command_ios_open;
std::vector<std::string> command_ios_close;
std::vector<std::string> set_before_command_open;
std::vector<std::string> set_after_command_open;
std::vector<std::string> reconfigure_command;
std::vector<double> command_ios_open_values;
std::vector<double> command_ios_close_values;
std::vector<double> set_before_command_open_values;
std::vector<double> set_after_command_open_values;
std::vector<double> reconfigure_command_values;
std::vector<std::string> state_ios_open;
std::vector<std::string> state_ios_close;
std::vector<std::string> set_before_command_close;
std::vector<std::string> set_after_command_close;
std::vector<double> state_ios_open_values;
std::vector<double> state_ios_close_values;
std::vector<double> set_before_command_close_values;
std::vector<double> set_after_command_close_values;
std::vector<double> set_after_command_open_values_original_;
std::string status_joint_name;
bool is_open;
std::unordered_map<std::string, double> command_if_ios_after_opening;
std::unordered_map<std::string, double> original_ios_after_opening;
std::unordered_map<std::string, double> command_if_ios_before_closing;
std::unordered_map<std::string, double> original_ios_before_closing;

std::unordered_set<std::string> command_if_ios, state_if_ios;

std::unordered_set<std::string> command_if_ios;
std::unordered_set<std::string> state_if_ios;
bool setResult;


using ControllerModeSrvType = std_srvs::srv::SetBool;
using OpenSrvType = std_srvs::srv::Trigger;
using ConfigSrvType = control_msgs::srv::SetConfig;
Expand All @@ -139,38 +166,29 @@ class IOGripperController : public controller_interface::ControllerInterface

protected:
std::shared_ptr<io_gripper_controller::ParamListener> param_listener_;

rclcpp::Service<OpenSrvType>::SharedPtr open_service_;
rclcpp::Service<OpenSrvType>::SharedPtr close_service_;
rclcpp::Service<ConfigSrvType>::SharedPtr configure_gripper_service_;

rclcpp_action::Server<GripperAction>::SharedPtr gripper_action_server_;
rclcpp_action::Server<GripperConfigAction>::SharedPtr gripper_config_action_server_;

realtime_tools::RealtimeBuffer<service_mode_type> service_buffer_;
realtime_tools::RealtimeBuffer<std::string> configure_gripper_buffer_;
realtime_tools::RealtimeBuffer<gripper_state_type> gripper_state_buffer_;
realtime_tools::RealtimeBuffer<reconfigure_state_type> reconfigure_state_buffer_;

using ControllerStatePublisher = realtime_tools::RealtimePublisher<ControllerStateMsg>;
using EventPublisher = realtime_tools::RealtimePublisher<EventStateMsg>;

using ConfigPublisher = realtime_tools::RealtimePublisher<ConfigJointMsg>;
using InterfacePublisher = realtime_tools::RealtimePublisher<InterfaceMsg>;

rclcpp::Publisher<ControllerStateMsg>::SharedPtr g_j_s_publisher_;
std::unique_ptr<ControllerStatePublisher> gripper_joint_state_publisher_;

std::vector<double> joint_state_values_;

rclcpp::Publisher<InterfaceMsg>::SharedPtr if_publisher_;
std::unique_ptr<InterfacePublisher> interface_publisher_;


rclcpp::Publisher<EventStateMsg>::SharedPtr e_publisher_;
std::unique_ptr<EventPublisher> event_publisher_;

std::atomic<bool> reconfigureFlag_{false}, openFlag_{false}, closeFlag_{false};
std::atomic<bool> reconfigureFlag_{false};
std::atomic<bool> openFlag_{false};
std::atomic<bool> closeFlag_{false};

private:
bool find_and_set_command(const std::string & name, const double value);
Expand All @@ -179,16 +197,13 @@ class IOGripperController : public controller_interface::ControllerInterface
void handle_gripper_state_transition_open(const gripper_state_type & state);
void handle_gripper_state_transition_close(const gripper_state_type & state);
void handle_reconfigure_state_transition(const reconfigure_state_type & state);
/// \brief Function to check the parameters
controller_interface::CallbackReturn check_parameters();
/// Preparing the command ios and states ios vars for the command/state interface configuraiton
void prepare_command_and_state_ios();
controller_interface::CallbackReturn prepare_publishers_and_services();
void publish_gripper_joint_states();
void publish_dynamic_interface_values();
void publish_reconfigure_gripper_joint_states();
void check_gripper_and_reconfigure_state();

std::vector<std::string> configurations_list_;
std::vector<io_gripper_controller::Params::ConfigurationSetup::MapConfigurations> config_map_;
std::vector<io_gripper_controller::Params::SensorsInterfaces::MapGripperSpecificSensors> sensors_map_;
Expand All @@ -199,32 +214,25 @@ class IOGripperController : public controller_interface::ControllerInterface
io_gripper_controller::Params::Close::State::MapPossibleClosedStates closed_state_values_;
io_gripper_controller::Params::ConfigurationSetup::MapConfigurations conf_it_;
std::vector<std::string>::iterator config_index_;

rclcpp::CallbackGroup::SharedPtr open_service_callback_group_, close_service_callback_group_, reconfigure_service_callback_group_;

rclcpp::CallbackGroup::SharedPtr open_service_callback_group_;
rclcpp::CallbackGroup::SharedPtr close_service_callback_group_;
rclcpp::CallbackGroup::SharedPtr reconfigure_service_callback_group_;
std::shared_ptr<control_msgs::action::Gripper_Feedback> gripper_feedback_;
std::shared_ptr<control_msgs::action::Gripper_Result> gripper_result_;
std::shared_ptr<control_msgs::action::SetGripperConfig_Feedback> gripper_config_feedback_;
std::shared_ptr<control_msgs::action::SetGripperConfig_Result> gripper_config_result_;

rclcpp_action::GoalResponse handle_goal(
const rclcpp_action::GoalUUID & uuid,
std::shared_ptr<const GripperAction::Goal> goal);

rclcpp_action::CancelResponse handle_cancel(
const std::shared_ptr<GoalHandleGripper> goal_handle);

void handle_accepted(const std::shared_ptr<GoalHandleGripper> goal_handle);
void execute(const std::shared_ptr<GoalHandleGripper> goal_handle);

rclcpp_action::GoalResponse config_handle_goal(
const rclcpp_action::GoalUUID & uuid,
std::shared_ptr<const GripperConfigAction::Goal> goal);


rclcpp_action::CancelResponse config_handle_cancel(
const std::shared_ptr<GoalHandleGripperConfig> goal_handle);

void config_handle_accepted(const std::shared_ptr<GoalHandleGripperConfig> goal_handle);
void config_execute(const std::shared_ptr<GoalHandleGripperConfig> goal_handle);
};
Expand Down
2 changes: 1 addition & 1 deletion io_gripper_controller/src/io_gripper_controller.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt) (template)
// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt)
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down
2 changes: 1 addition & 1 deletion io_gripper_controller/test/test_io_gripper_controller.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt) (template)
// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt)
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down
2 changes: 1 addition & 1 deletion io_gripper_controller/test/test_io_gripper_controller.hpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt) (template)
// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt)
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt) (template)
// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt)
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down
Loading

0 comments on commit 4640609

Please sign in to comment.