ros2_control - rolling
Loading...
Searching...
No Matches
parallel_gripper_action_controller.hpp
1// Copyright 2014, SRI International
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
16
17#ifndef PARALLEL_GRIPPER_CONTROLLER__PARALLEL_GRIPPER_ACTION_CONTROLLER_HPP_
18#define PARALLEL_GRIPPER_CONTROLLER__PARALLEL_GRIPPER_ACTION_CONTROLLER_HPP_
19
20// C++ standard
21#include <cassert>
22#include <memory>
23#include <stdexcept>
24#include <string>
25
26// ROS
27#include "rclcpp/rclcpp.hpp"
28
29// ROS messages
30#include "control_msgs/action/parallel_gripper_command.hpp"
31
32// rclcpp_action
33#include "rclcpp_action/create_server.hpp"
34
35// ros_controls
36#include "controller_interface/controller_interface.hpp"
37#include "hardware_interface/loaned_command_interface.hpp"
38#include "hardware_interface/loaned_state_interface.hpp"
39#include "realtime_tools/realtime_server_goal_handle.hpp"
40#include "realtime_tools/realtime_thread_safe_box.hpp"
41
42// Project
43#include "parallel_gripper_controller/parallel_gripper_action_controller_parameters.hpp"
44
46{
56{
57public:
62 struct Commands
63 {
64 double position_cmd_; // Commanded position
65 double max_velocity_; // Desired max gripper velocity
66 double max_effort_; // Desired max allowed effort
67 };
69
75
81
82 controller_interface::return_type update(
83 const rclcpp::Time & time, const rclcpp::Duration & period) override;
84
85 controller_interface::CallbackReturn on_init() override;
86
87 controller_interface::CallbackReturn on_configure(
88 const rclcpp_lifecycle::State & previous_state) override;
89
90 controller_interface::CallbackReturn on_activate(
91 const rclcpp_lifecycle::State & previous_state) override;
92
93 controller_interface::CallbackReturn on_deactivate(
94 const rclcpp_lifecycle::State & previous_state) override;
95
96protected:
97 using GripperCommandAction = control_msgs::action::ParallelGripperCommand;
98 using ActionServer = rclcpp_action::Server<GripperCommandAction>;
99 using ActionServerPtr = ActionServer::SharedPtr;
100 using GoalHandle = rclcpp_action::ServerGoalHandle<GripperCommandAction>;
101 using RealtimeGoalHandle =
103 using RealtimeGoalHandlePtr = std::shared_ptr<RealtimeGoalHandle>;
105
106 // the realtime container to exchange the reference from subscriber
108 // pre-allocated memory that is reused
109 Commands command_struct_;
110 // save the last reference in case of unable to get value from box
111 Commands command_struct_rt_;
112
113 std::string name_;
114 std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
115 joint_command_interface_;
116 std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
117 effort_interface_;
118 std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
119 speed_interface_;
120 std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
121 joint_position_state_interface_;
122 std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
123 joint_velocity_state_interface_;
124
125 std::shared_ptr<ParamListener> param_listener_;
126 Params params_;
127
130 control_msgs::action::ParallelGripperCommand::Result::SharedPtr pre_alloc_result_;
131
132 rclcpp::Duration action_monitor_period_;
133
134 // ROS API
135 ActionServerPtr action_server_;
136
137 rclcpp::TimerBase::SharedPtr goal_handle_timer_;
138
139 rclcpp_action::GoalResponse goal_callback(
140 const rclcpp_action::GoalUUID & uuid, std::shared_ptr<const GripperCommandAction::Goal> goal);
141
142 rclcpp_action::CancelResponse cancel_callback(const std::shared_ptr<GoalHandle> goal_handle);
143
144 void accepted_callback(std::shared_ptr<GoalHandle> goal_handle);
145
146 void preempt_active_goal();
147
148 void set_hold_position();
149
152
157 const rclcpp::Time & time, double error_position, double current_position,
158 double current_velocity);
159};
160
161} // namespace parallel_gripper_action_controller
162
163#include "parallel_gripper_controller/parallel_gripper_action_controller_impl.hpp"
164
165#endif // PARALLEL_GRIPPER_CONTROLLER__PARALLEL_GRIPPER_ACTION_CONTROLLER_HPP_
Definition controller_interface.hpp:27
Controller for executing a ParallelGripperCommand action.
Definition parallel_gripper_action_controller.hpp:56
controller_interface::return_type update(const rclcpp::Time &time, const rclcpp::Duration &period) override
Definition parallel_gripper_action_controller_impl.hpp:59
RealtimeGoalHandleBox rt_active_goal_
Container for the currently active action goal, if any.
Definition parallel_gripper_action_controller.hpp:129
double computed_command_
Computed command.
Definition parallel_gripper_action_controller.hpp:151
controller_interface::InterfaceConfiguration command_interface_configuration() const override
command_interface_configuration This controller requires the position command interfaces for the cont...
Definition parallel_gripper_action_controller_impl.hpp:412
std::string name_
Controller name.
Definition parallel_gripper_action_controller.hpp:113
controller_interface::InterfaceConfiguration state_interface_configuration() const override
command_interface_configuration This controller requires the position and velocity state interfaces f...
Definition parallel_gripper_action_controller_impl.hpp:428
realtime_tools::RealtimeThreadSafeBox< rclcpp::Time > last_movement_time_
Store stall time.
Definition parallel_gripper_action_controller.hpp:150
controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition parallel_gripper_action_controller_impl.hpp:44
void check_for_success(const rclcpp::Time &time, double error_position, double current_position, double current_velocity)
Check for success and publish appropriate result and feedback.
Definition parallel_gripper_action_controller_impl.hpp:214
Definition realtime_server_goal_handle.hpp:44
Definition parallel_gripper_action_controller.hpp:46
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:58
Store position and max effort in struct to allow easier realtime buffer usage.
Definition parallel_gripper_action_controller.hpp:63