ros2_control - iron
Loading...
Searching...
No Matches
admittance_controller.hpp
1// Copyright (c) 2022, PickNik, Inc.
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 ADMITTANCE_CONTROLLER__ADMITTANCE_CONTROLLER_HPP_
18#define ADMITTANCE_CONTROLLER__ADMITTANCE_CONTROLLER_HPP_
19
20#include <chrono>
21#include <memory>
22#include <string>
23#include <vector>
24
25// auto-generated by generate_parameter_library
26#include "admittance_controller_parameters.hpp"
27
28#include "admittance_controller/admittance_rule.hpp"
29#include "admittance_controller/visibility_control.h"
30#include "control_msgs/msg/admittance_controller_state.hpp"
31#include "controller_interface/chainable_controller_interface.hpp"
32#include "geometry_msgs/msg/pose_stamped.hpp"
33#include "geometry_msgs/msg/transform_stamped.hpp"
34#include "geometry_msgs/msg/wrench_stamped.hpp"
35#include "hardware_interface/types/hardware_interface_type_values.hpp"
36#include "pluginlib/class_loader.hpp"
37#include "rclcpp/duration.hpp"
38#include "rclcpp/time.hpp"
39#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
40#include "rclcpp_lifecycle/state.hpp"
41#include "realtime_tools/realtime_buffer.h"
42#include "realtime_tools/realtime_publisher.h"
43#include "semantic_components/force_torque_sensor.hpp"
44
45#include "trajectory_msgs/msg/joint_trajectory.hpp"
46
48{
49using ControllerStateMsg = control_msgs::msg::AdmittanceControllerState;
50
52{
53public:
54 ADMITTANCE_CONTROLLER_PUBLIC
55 controller_interface::CallbackReturn on_init() override;
56
58
62 ADMITTANCE_CONTROLLER_PUBLIC
64
66
70 ADMITTANCE_CONTROLLER_PUBLIC
72
73 ADMITTANCE_CONTROLLER_PUBLIC
74 controller_interface::CallbackReturn on_configure(
75 const rclcpp_lifecycle::State & previous_state) override;
76
77 ADMITTANCE_CONTROLLER_PUBLIC
78 controller_interface::CallbackReturn on_activate(
79 const rclcpp_lifecycle::State & previous_state) override;
80
81 ADMITTANCE_CONTROLLER_PUBLIC
82 controller_interface::CallbackReturn on_deactivate(
83 const rclcpp_lifecycle::State & previous_state) override;
84
85 ADMITTANCE_CONTROLLER_PUBLIC
86 controller_interface::CallbackReturn on_cleanup(
87 const rclcpp_lifecycle::State & previous_state) override;
88
89 ADMITTANCE_CONTROLLER_PUBLIC
90 controller_interface::CallbackReturn on_error(
91 const rclcpp_lifecycle::State & previous_state) override;
92
93 ADMITTANCE_CONTROLLER_PUBLIC
94 controller_interface::return_type update_and_write_commands(
95 const rclcpp::Time & time, const rclcpp::Duration & period) override;
96
97protected:
98 std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces() override;
99
100 controller_interface::return_type update_reference_from_subscribers(
101 const rclcpp::Time & time, const rclcpp::Duration & period) override;
102
103 size_t num_joints_ = 0;
104 std::vector<std::string> command_joint_names_;
105
106 // The interfaces are defined as the types in 'allowed_interface_types_' member.
107 // For convenience, for each type the interfaces are ordered so that i-th position
108 // matches i-th index in joint_names_
109 template <typename T>
110 using InterfaceReferences = std::vector<std::vector<std::reference_wrapper<T>>>;
111
112 InterfaceReferences<hardware_interface::LoanedCommandInterface> joint_command_interface_;
113 InterfaceReferences<hardware_interface::LoanedStateInterface> joint_state_interface_;
114
115 bool has_position_state_interface_ = false;
116 bool has_velocity_state_interface_ = false;
117 bool has_acceleration_state_interface_ = false;
118 bool has_position_command_interface_ = false;
119 bool has_velocity_command_interface_ = false;
120 bool has_acceleration_command_interface_ = false;
121 bool has_effort_command_interface_ = false;
122
123 // To reduce number of variables and to make the code shorter the interfaces are ordered in types
124 // as the following constants
125 const std::vector<std::string> allowed_interface_types_ = {
128
129 // internal reference values
130 const std::vector<std::string> allowed_reference_interfaces_types_ = {
132 std::vector<std::reference_wrapper<double>> position_reference_;
133 std::vector<std::reference_wrapper<double>> velocity_reference_;
134
135 // Admittance rule and dependent variables;
136 std::unique_ptr<admittance_controller::AdmittanceRule> admittance_;
137
138 // force torque sensor
139 std::unique_ptr<semantic_components::ForceTorqueSensor> force_torque_sensor_;
140
141 // ROS subscribers
142 rclcpp::Subscription<trajectory_msgs::msg::JointTrajectoryPoint>::SharedPtr
143 input_joint_command_subscriber_;
144 rclcpp::Publisher<control_msgs::msg::AdmittanceControllerState>::SharedPtr s_publisher_;
145
146 // admittance parameters
147 std::shared_ptr<admittance_controller::ParamListener> parameter_handler_;
148
149 // ROS messages
150 std::shared_ptr<trajectory_msgs::msg::JointTrajectoryPoint> joint_command_msg_;
151
152 // real-time buffer
154 input_joint_command_;
155 std::unique_ptr<realtime_tools::RealtimePublisher<ControllerStateMsg>> state_publisher_;
156
157 trajectory_msgs::msg::JointTrajectoryPoint last_commanded_;
158 trajectory_msgs::msg::JointTrajectoryPoint last_reference_;
159
160 // control loop data
161 // reference_: reference value read by the controller
162 // joint_state_: current joint readings from the hardware
163 // reference_admittance_: reference value used by the controller after the admittance values are
164 // applied ft_values_: values read from the force torque sensor
165 trajectory_msgs::msg::JointTrajectoryPoint reference_, joint_state_, reference_admittance_;
166 geometry_msgs::msg::Wrench ft_values_;
167
173 trajectory_msgs::msg::JointTrajectoryPoint & state_current,
174 geometry_msgs::msg::Wrench & ft_values);
175
180 void read_state_reference_interfaces(trajectory_msgs::msg::JointTrajectoryPoint & state);
181
185 void write_state_to_hardware(const trajectory_msgs::msg::JointTrajectoryPoint & state_command);
186};
187
188} // namespace admittance_controller
189
190#endif // ADMITTANCE_CONTROLLER__ADMITTANCE_CONTROLLER_HPP_
Definition admittance_controller.hpp:52
controller_interface::return_type update_reference_from_subscribers(const rclcpp::Time &time, const rclcpp::Duration &period) override
Update reference from input topics when not in chained mode.
Definition admittance_controller.cpp:362
std::vector< hardware_interface::CommandInterface > on_export_reference_interfaces() override
Definition admittance_controller.cpp:105
ADMITTANCE_CONTROLLER_PUBLIC controller_interface::return_type update_and_write_commands(const rclcpp::Time &time, const rclcpp::Duration &period) override
Execute calculations of the controller and update command interfaces.
Definition admittance_controller.cpp:389
ADMITTANCE_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration() const override
Export configuration of required state interfaces.
Definition admittance_controller.cpp:64
void read_state_from_hardware(trajectory_msgs::msg::JointTrajectoryPoint &state_current, geometry_msgs::msg::Wrench &ft_values)
Read values from hardware interfaces and set corresponding fields of state_current and ft_values.
Definition admittance_controller.cpp:464
void write_state_to_hardware(const trajectory_msgs::msg::JointTrajectoryPoint &state_command)
Write values from state_command to claimed hardware interfaces.
Definition admittance_controller.cpp:522
ADMITTANCE_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition admittance_controller.cpp:34
void read_state_reference_interfaces(trajectory_msgs::msg::JointTrajectoryPoint &state)
Set fields of state_reference with values from controllers exported position and velocity references.
Definition admittance_controller.cpp:550
ADMITTANCE_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration() const override
Export configuration of required state interfaces.
Definition admittance_controller.cpp:82
Definition chainable_controller_interface.hpp:35
Definition realtime_buffer.hpp:44
Definition admittance_controller.hpp:48
constexpr char HW_IF_ACCELERATION[]
Constant defining acceleration interface.
Definition hardware_interface_type_values.hpp:25
constexpr char HW_IF_VELOCITY[]
Constant defining velocity interface.
Definition hardware_interface_type_values.hpp:23
constexpr char HW_IF_POSITION[]
Constant defining position interface.
Definition hardware_interface_type_values.hpp:21
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:56