Skip to content

Commit

Permalink
rename controller
Browse files Browse the repository at this point in the history
Signed-off-by: Paul Gesel <paulgesel@gmail.com>
  • Loading branch information
pac48 committed Apr 2, 2024
1 parent e2cc8eb commit 6b44ba8
Show file tree
Hide file tree
Showing 15 changed files with 136 additions and 136 deletions.
84 changes: 0 additions & 84 deletions antipodal_gripper_controller/CMakeLists.txt

This file was deleted.

10 changes: 0 additions & 10 deletions antipodal_gripper_controller/ros_control_plugins.xml

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ controller_interface::CallbackReturn GripperActionController<HardwareInterface>:
get_node()->get_logger(),
"[Deprecated]: the `position_controllers/GripperActionController` and "
"`effort_controllers::GripperActionController` controllers are replaced by "
"'antipodal_gripper_controllers/GripperActionController' controller");
"'parallel_gripper_controllers/GripperActionController' controller");
try
{
param_listener_ = std::make_shared<ParamListener>(get_node());
Expand Down
84 changes: 84 additions & 0 deletions parallel_gripper_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,84 @@
cmake_minimum_required(VERSION 3.16)
project(parallel_gripper_controller LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
control_msgs
control_toolbox
controller_interface
generate_parameter_library
hardware_interface
pluginlib
rclcpp
rclcpp_action
realtime_tools
)

find_package(ament_cmake REQUIRED)
find_package(backward_ros REQUIRED)
foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
find_package(${Dependency} REQUIRED)
endforeach()

generate_parameter_library(parallel_gripper_action_controller_parameters
src/parallel_gripper_action_controller_parameters.yaml
)

add_library(parallel_gripper_action_controller SHARED
src/parallel_gripper_action_controller.cpp
)
target_compile_features(parallel_gripper_action_controller PUBLIC cxx_std_17)
target_include_directories(parallel_gripper_action_controller PUBLIC
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include/parallel_gripper_action_controller>
)
target_link_libraries(parallel_gripper_action_controller PUBLIC
parallel_gripper_action_controller_parameters
)
ament_target_dependencies(parallel_gripper_action_controller PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS})

pluginlib_export_plugin_description_file(controller_interface ros_control_plugins.xml)

if(BUILD_TESTING)
find_package(ament_cmake_gmock REQUIRED)
find_package(controller_manager REQUIRED)
find_package(ros2_control_test_assets REQUIRED)

ament_add_gmock(test_load_parallel_gripper_action_controllers
test/test_load_parallel_gripper_action_controller.cpp
)
ament_target_dependencies(test_load_parallel_gripper_action_controllers
controller_manager
ros2_control_test_assets
)

ament_add_gmock(test_parallel_gripper_controller
test/test_parallel_gripper_controller.cpp
)
target_link_libraries(test_parallel_gripper_controller
parallel_gripper_action_controller
)
endif()

install(
DIRECTORY include/
DESTINATION include/parallel_gripper_action_controller
)
install(
TARGETS
parallel_gripper_action_controller
parallel_gripper_action_controller_parameters
EXPORT export_parallel_gripper_action_controller
RUNTIME DESTINATION bin
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
INCLUDES DESTINATION include
)

ament_export_targets(export_parallel_gripper_action_controller HAS_LIBRARY_TARGET)
ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS})
ament_package()
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
:github_url: https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/antipodal_gripper_controller/doc/userdoc.rst
:github_url: https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/parallel_gripper_controller/doc/userdoc.rst

.. _antipodal_gripper_controller_userdoc:
.. _parallel_gripper_controller_userdoc:

Antipodal Gripper Action Controller
Parallel Gripper Action Controller
-----------------------------------

Controller for executing a ``AntipodalGripperCommand`` action for simple antipodal grippers.
Controller for executing a ``ParallelGripperCommand`` action for simple parallel grippers.
This controller supports grippers that offer position only control as well as grippers that allow configuring the velocity and effort.
By default, the controller will only claim the `{joint}/position` interface for control.
The velocity and effort interfaces can be optionally claimed by setting the `max_velocity_interface` and `max_effort_interface` parameter, respectively.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,8 @@

/// \author Sachin Chitta, Adolfo Rodriguez Tsouroukdissian

#ifndef ANTIPODAL_GRIPPER_CONTROLLER__GRIPPER_ACTION_CONTROLLER_HPP_
#define ANTIPODAL_GRIPPER_CONTROLLER__GRIPPER_ACTION_CONTROLLER_HPP_
#ifndef PARALLEL_GRIPPER_CONTROLLER__GRIPPER_ACTION_CONTROLLER_HPP_
#define PARALLEL_GRIPPER_CONTROLLER__GRIPPER_ACTION_CONTROLLER_HPP_

// C++ standard
#include <cassert>
Expand All @@ -27,26 +27,26 @@
#include "rclcpp/rclcpp.hpp"

// ROS messages
#include "control_msgs/action/antipodal_gripper_command.hpp"
#include "control_msgs/action/parallel_gripper_command.hpp"

// rclcpp_action
#include "rclcpp_action/create_server.hpp"

// ros_controls
#include "antipodal_gripper_controller/visibility_control.hpp"
#include "parallel_gripper_controller/visibility_control.hpp"
#include "controller_interface/controller_interface.hpp"
#include "hardware_interface/loaned_command_interface.hpp"
#include "hardware_interface/loaned_state_interface.hpp"
#include "realtime_tools/realtime_buffer.h"
#include "realtime_tools/realtime_server_goal_handle.h"

// Project
#include "antipodal_gripper_action_controller_parameters.hpp"
#include "parallel_gripper_action_controller_parameters.hpp"

namespace antipodal_gripper_action_controller
namespace parallel_gripper_action_controller
{
/**
* \brief Controller for executing a `AntipodalGripperCommand` action.
* \brief Controller for executing a `ParallelGripperCommand` action.
*
* \tparam HardwareInterface Controller hardware interface. Currently \p
* hardware_interface::HW_IF_POSITION and \p
Expand Down Expand Up @@ -107,12 +107,12 @@ class GripperActionController : public controller_interface::ControllerInterface
Commands command_struct_, command_struct_rt_;

protected:
using GripperCommandAction = control_msgs::action::AntipodalGripperCommand;
using GripperCommandAction = control_msgs::action::ParallelGripperCommand;
using ActionServer = rclcpp_action::Server<GripperCommandAction>;
using ActionServerPtr = ActionServer::SharedPtr;
using GoalHandle = rclcpp_action::ServerGoalHandle<GripperCommandAction>;
using RealtimeGoalHandle =
realtime_tools::RealtimeServerGoalHandle<control_msgs::action::AntipodalGripperCommand>;
realtime_tools::RealtimeServerGoalHandle<control_msgs::action::ParallelGripperCommand>;
using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
using RealtimeGoalHandleBuffer = realtime_tools::RealtimeBuffer<RealtimeGoalHandlePtr>;

Expand All @@ -136,7 +136,7 @@ class GripperActionController : public controller_interface::ControllerInterface

RealtimeGoalHandleBuffer
rt_active_goal_; ///< Container for the currently active action goal, if any.
control_msgs::action::AntipodalGripperCommand::Result::SharedPtr pre_alloc_result_;
control_msgs::action::ParallelGripperCommand::Result::SharedPtr pre_alloc_result_;

rclcpp::Duration action_monitor_period_;

Expand Down Expand Up @@ -167,8 +167,8 @@ class GripperActionController : public controller_interface::ControllerInterface
double current_velocity);
};

} // namespace antipodal_gripper_action_controller
} // namespace parallel_gripper_action_controller

#include "antipodal_gripper_controller/antipodal_gripper_action_controller_impl.hpp"
#include "parallel_gripper_controller/parallel_gripper_action_controller_impl.hpp"

#endif // ANTIPODAL_GRIPPER_CONTROLLER__GRIPPER_ACTION_CONTROLLER_HPP_
#endif // PARALLEL_GRIPPER_CONTROLLER__GRIPPER_ACTION_CONTROLLER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -14,16 +14,16 @@

/// \author Sachin Chitta, Adolfo Rodriguez Tsouroukdissian, Stu Glaser

#ifndef ANTIPODAL_GRIPPER_CONTROLLER__GRIPPER_ACTION_CONTROLLER_IMPL_HPP_
#define ANTIPODAL_GRIPPER_CONTROLLER__GRIPPER_ACTION_CONTROLLER_IMPL_HPP_
#ifndef PARALLEL_GRIPPER_CONTROLLER__GRIPPER_ACTION_CONTROLLER_IMPL_HPP_
#define PARALLEL_GRIPPER_CONTROLLER__GRIPPER_ACTION_CONTROLLER_IMPL_HPP_

#include "antipodal_gripper_controller/antipodal_gripper_action_controller.hpp"
#include "parallel_gripper_controller/parallel_gripper_action_controller.hpp"

#include <hardware_interface/types/hardware_interface_type_values.hpp>
#include <memory>
#include <string>

namespace antipodal_gripper_action_controller
namespace parallel_gripper_action_controller
{

void GripperActionController::preempt_active_goal()
Expand Down Expand Up @@ -83,7 +83,7 @@ rclcpp_action::GoalResponse GripperActionController::goal_callback(
{
if (goal_handle->command.position.size() != 1)
{
pre_alloc_result_ = std::make_shared<control_msgs::action::AntipodalGripperCommand::Result>();
pre_alloc_result_ = std::make_shared<control_msgs::action::ParallelGripperCommand::Result>();
pre_alloc_result_->state.position.resize(1);
pre_alloc_result_->state.effort.resize(1);
RCLCPP_ERROR(
Expand Down Expand Up @@ -332,15 +332,15 @@ controller_interface::CallbackReturn GripperActionController::on_activate(
command_.initRT(command_struct_);

// Result
pre_alloc_result_ = std::make_shared<control_msgs::action::AntipodalGripperCommand::Result>();
pre_alloc_result_ = std::make_shared<control_msgs::action::ParallelGripperCommand::Result>();
pre_alloc_result_->state.position.resize(1);
pre_alloc_result_->state.effort.resize(1);
pre_alloc_result_->state.position[0] = command_struct_.position_cmd_;
pre_alloc_result_->reached_goal = false;
pre_alloc_result_->stalled = false;

// Action interface
action_server_ = rclcpp_action::create_server<control_msgs::action::AntipodalGripperCommand>(
action_server_ = rclcpp_action::create_server<control_msgs::action::ParallelGripperCommand>(
get_node(), "~/gripper_cmd",
std::bind(
&GripperActionController::goal_callback, this, std::placeholders::_1, std::placeholders::_2),
Expand Down Expand Up @@ -393,6 +393,6 @@ GripperActionController::GripperActionController()
{
}

} // namespace antipodal_gripper_action_controller
} // namespace parallel_gripper_action_controller

#endif // ANTIPODAL_GRIPPER_CONTROLLER__GRIPPER_ACTION_CONTROLLER_IMPL_HPP_
#endif // PARALLEL_GRIPPER_CONTROLLER__GRIPPER_ACTION_CONTROLLER_IMPL_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,8 @@
* library cannot have, but the consuming code must have inorder to link.
*/

#ifndef ANTIPODAL_GRIPPER_CONTROLLER__VISIBILITY_CONTROL_HPP_
#define ANTIPODAL_GRIPPER_CONTROLLER__VISIBILITY_CONTROL_HPP_
#ifndef PARALLEL_GRIPPER_CONTROLLER__VISIBILITY_CONTROL_HPP_
#define PARALLEL_GRIPPER_CONTROLLER__VISIBILITY_CONTROL_HPP_

// This logic was borrowed (then namespaced) from the examples on the gcc wiki:
// https://gcc.gnu.org/wiki/Visibility
Expand Down Expand Up @@ -53,4 +53,4 @@
#define GRIPPER_ACTION_CONTROLLER_PUBLIC_TYPE
#endif

#endif // ANTIPODAL_GRIPPER_CONTROLLER__VISIBILITY_CONTROL_HPP_
#endif // PARALLEL_GRIPPER_CONTROLLER__VISIBILITY_CONTROL_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,9 @@
href="http://download.ros.org/schema/package_format3.xsd"
schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>antipodal_gripper_controller</name>
<name>parallel_gripper_controller</name>
<version>2.32.0</version>
<description>The antipodal_gripper_controller package</description>
<description>The parallel_gripper_controller package</description>
<maintainer email="bence.magyar.robotics@gmail.com">Bence Magyar</maintainer>

<license>Apache License 2.0</license>
Expand Down
10 changes: 10 additions & 0 deletions parallel_gripper_controller/ros_control_plugins.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
<library path="parallel_gripper_action_controller">

<class name="parallel_gripper_action_controller/GripperActionController"
type="parallel_gripper_action_controller::GripperActionController"
base_class_type="controller_interface::ControllerInterface">
<description>
</description>
</class>

</library>
Original file line number Diff line number Diff line change
Expand Up @@ -15,11 +15,11 @@
/// \author Sachin Chitta

// Project
#include <antipodal_gripper_controller/antipodal_gripper_action_controller.hpp>
#include <parallel_gripper_controller/parallel_gripper_action_controller.hpp>
#include <hardware_interface/types/hardware_interface_type_values.hpp>

#include "pluginlib/class_list_macros.hpp"

PLUGINLIB_EXPORT_CLASS(
antipodal_gripper_action_controller::GripperActionController,
parallel_gripper_action_controller::GripperActionController,
controller_interface::ControllerInterface)
Loading

0 comments on commit 6b44ba8

Please sign in to comment.