ros2_control - rolling
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 <memory>
21#include <string>
22#include <vector>
23
24// auto-generated by generate_parameter_library
25#include "admittance_controller/admittance_controller_parameters.hpp"
26
27#include "admittance_controller/admittance_rule.hpp"
28#include "control_msgs/msg/admittance_controller_state.hpp"
29#include "controller_interface/chainable_controller_interface.hpp"
30#include "hardware_interface/types/hardware_interface_type_values.hpp"
31#include "rclcpp/duration.hpp"
32#include "rclcpp/time.hpp"
33#include "rclcpp_lifecycle/state.hpp"
34#include "realtime_tools/realtime_buffer.hpp"
35#include "realtime_tools/realtime_publisher.hpp"
36#include "semantic_components/force_torque_sensor.hpp"
37
39{
40using ControllerStateMsg = control_msgs::msg::AdmittanceControllerState;
41
43{
44public:
45 controller_interface::CallbackReturn on_init() override;
46
48
53
55
60
61 controller_interface::CallbackReturn on_configure(
62 const rclcpp_lifecycle::State & previous_state) override;
63
64 controller_interface::CallbackReturn on_activate(
65 const rclcpp_lifecycle::State & previous_state) override;
66
67 controller_interface::CallbackReturn on_deactivate(
68 const rclcpp_lifecycle::State & previous_state) override;
69
70 controller_interface::CallbackReturn on_error(
71 const rclcpp_lifecycle::State & previous_state) override;
72
73 controller_interface::return_type update_and_write_commands(
74 const rclcpp::Time & time, const rclcpp::Duration & period) override;
75
76protected:
77 std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces() override;
78
79 controller_interface::return_type update_reference_from_subscribers(
80 const rclcpp::Time & time, const rclcpp::Duration & period) override;
81
82 size_t num_joints_ = 0;
83 std::vector<std::string> command_joint_names_;
84
85 // The interfaces are defined as the types in 'allowed_interface_types_' member.
86 // For convenience, for each type the interfaces are ordered so that i-th position
87 // matches i-th index in joint_names_
88 template <typename T>
89 using InterfaceReferences = std::vector<std::vector<std::reference_wrapper<T>>>;
90
91 InterfaceReferences<hardware_interface::LoanedCommandInterface> joint_command_interface_;
92 InterfaceReferences<hardware_interface::LoanedStateInterface> joint_state_interface_;
93
94 bool has_position_state_interface_ = false;
95 bool has_velocity_state_interface_ = false;
96 bool has_acceleration_state_interface_ = false;
97 bool has_position_command_interface_ = false;
98 bool has_velocity_command_interface_ = false;
99 bool has_acceleration_command_interface_ = false;
100 bool has_effort_command_interface_ = false;
101
102 // To reduce number of variables and to make the code shorter the interfaces are ordered in types
103 // as the following constants
104 const std::vector<std::string> allowed_interface_types_ = {
107
108 // internal reference values
109 const std::vector<std::string> allowed_reference_interfaces_types_ = {
111 std::vector<std::reference_wrapper<double>> position_reference_;
112 std::vector<std::reference_wrapper<double>> velocity_reference_;
113
114 // Admittance rule and dependent variables;
115 std::unique_ptr<admittance_controller::AdmittanceRule> admittance_;
116
117 // force torque sensor
118 std::unique_ptr<semantic_components::ForceTorqueSensor> force_torque_sensor_;
119
120 // ROS subscribers
121 rclcpp::Subscription<trajectory_msgs::msg::JointTrajectoryPoint>::SharedPtr
122 input_joint_command_subscriber_;
123 rclcpp::Subscription<geometry_msgs::msg::WrenchStamped>::SharedPtr
124 input_wrench_command_subscriber_;
125 rclcpp::Publisher<control_msgs::msg::AdmittanceControllerState>::SharedPtr s_publisher_;
126
127 // admittance parameters
128 std::shared_ptr<admittance_controller::ParamListener> parameter_handler_;
129
130 // ROS messages
131 std::shared_ptr<trajectory_msgs::msg::JointTrajectoryPoint> joint_command_msg_;
132
133 // real-time buffer
135 input_joint_command_;
137 std::unique_ptr<realtime_tools::RealtimePublisher<ControllerStateMsg>> state_publisher_;
138
139 trajectory_msgs::msg::JointTrajectoryPoint last_commanded_;
140 trajectory_msgs::msg::JointTrajectoryPoint last_reference_;
141
142 // control loop data
143 // reference_: reference value read by the controller
144 // joint_state_: current joint readings from the hardware
145 // reference_admittance_: reference value used by the controller after the admittance values are
146 // applied ft_values_: values read from the force torque sensor
147 trajectory_msgs::msg::JointTrajectoryPoint reference_, joint_state_, reference_admittance_;
148 geometry_msgs::msg::Wrench ft_values_;
149
155 trajectory_msgs::msg::JointTrajectoryPoint & state_current,
156 geometry_msgs::msg::Wrench & ft_values);
157
162 void read_state_reference_interfaces(trajectory_msgs::msg::JointTrajectoryPoint & state);
163
167 void write_state_to_hardware(const trajectory_msgs::msg::JointTrajectoryPoint & state_command);
168};
169
170} // namespace admittance_controller
171
172#endif // ADMITTANCE_CONTROLLER__ADMITTANCE_CONTROLLER_HPP_
Definition admittance_controller.hpp:43
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:395
std::vector< hardware_interface::CommandInterface > on_export_reference_interfaces() override
Definition admittance_controller.cpp:118
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:422
controller_interface::InterfaceConfiguration command_interface_configuration() const override
Export configuration of required state interfaces.
Definition admittance_controller.cpp:77
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:493
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:551
controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition admittance_controller.cpp:47
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:579
controller_interface::InterfaceConfiguration state_interface_configuration() const override
Export configuration of required state interfaces.
Definition admittance_controller.cpp:95
Definition chainable_controller_interface.hpp:37
Definition realtime_buffer.hpp:44
Definition admittance_controller.hpp:39
constexpr char HW_IF_ACCELERATION[]
Constant defining acceleration interface name.
Definition hardware_interface_type_values.hpp:25
constexpr char HW_IF_VELOCITY[]
Constant defining velocity interface name.
Definition hardware_interface_type_values.hpp:23
constexpr char HW_IF_POSITION[]
Constant defining position interface name.
Definition hardware_interface_type_values.hpp:21
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:57