ros2_control - rolling
Loading...
Searching...
No Matches
pid_controller.hpp
1// Copyright (c) 2023, Stogl Robotics Consulting UG (haftungsbeschränkt)
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//
15// Authors: Daniel Azanov, Dr. Denis
16//
17
18#ifndef PID_CONTROLLER__PID_CONTROLLER_HPP_
19#define PID_CONTROLLER__PID_CONTROLLER_HPP_
20
21#include <atomic>
22#include <memory>
23#include <string>
24#include <vector>
25
26#include "control_msgs/msg/multi_dof_command.hpp"
27#include "control_msgs/msg/multi_dof_state_stamped.hpp"
28#include "control_toolbox/pid_ros.hpp"
29#include "controller_interface/chainable_controller_interface.hpp"
30#include "rclcpp_lifecycle/state.hpp"
31#include "realtime_tools/realtime_publisher.hpp"
32#include "realtime_tools/realtime_thread_safe_box.hpp"
33#include "std_srvs/srv/set_bool.hpp"
34
35#include "pid_controller/pid_controller_parameters.hpp"
36
37namespace pid_controller
38{
39
41{
42public:
44
45 controller_interface::CallbackReturn on_init() override;
46
48
50
51 controller_interface::CallbackReturn on_cleanup(
52 const rclcpp_lifecycle::State & previous_state) override;
53
54 controller_interface::CallbackReturn on_configure(
55 const rclcpp_lifecycle::State & previous_state) override;
56
57 controller_interface::CallbackReturn on_activate(
58 const rclcpp_lifecycle::State & previous_state) override;
59
60 controller_interface::return_type update_reference_from_subscribers(
61 const rclcpp::Time & time, const rclcpp::Duration & period) override;
62
63 controller_interface::return_type update_and_write_commands(
64 const rclcpp::Time & time, const rclcpp::Duration & period) override;
65
66 using ControllerReferenceMsg = control_msgs::msg::MultiDOFCommand;
67 using ControllerMeasuredStateMsg = control_msgs::msg::MultiDOFCommand;
68 using ControllerModeSrvType = std_srvs::srv::SetBool;
69 using ControllerStateMsg = control_msgs::msg::MultiDOFStateStamped;
70
71protected:
72 std::shared_ptr<pid_controller::ParamListener> param_listener_;
73 pid_controller::Params params_;
74
75 std::vector<std::string> reference_and_state_dof_names_;
76 size_t dof_;
77 std::vector<double> measured_state_values_;
78
79 using PidPtr = std::shared_ptr<control_toolbox::PidROS>;
80 std::vector<PidPtr> pids_;
81
82 // Command subscribers and Controller State publisher
83 rclcpp::Subscription<ControllerReferenceMsg>::SharedPtr ref_subscriber_ = nullptr;
85 ControllerReferenceMsg current_ref_;
86
87 rclcpp::Subscription<ControllerMeasuredStateMsg>::SharedPtr measured_state_subscriber_ = nullptr;
89 ControllerMeasuredStateMsg current_state_;
90
92
93 rclcpp::Publisher<ControllerStateMsg>::SharedPtr s_publisher_;
94 std::unique_ptr<ControllerStatePublisher> state_publisher_;
95
96 // override methods from ChainableControllerInterface
97 std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces() override;
98
99 std::vector<hardware_interface::StateInterface> on_export_state_interfaces() override;
100
101 bool on_set_chained_mode(bool chained_mode) override;
102
103 // internal methods
104 controller_interface::CallbackReturn configure_parameters();
105
106private:
107 // callback for topic interface
108 void reference_callback(const std::shared_ptr<ControllerReferenceMsg> msg);
109};
110
111} // namespace pid_controller
112
113#endif // PID_CONTROLLER__PID_CONTROLLER_HPP_
Definition chainable_controller_interface.hpp:37
Definition pid_controller.hpp:41
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 pid_controller.cpp:455
bool on_set_chained_mode(bool chained_mode) override
Virtual method that each chainable controller should implement to switch chained mode.
Definition pid_controller.cpp:396
std::vector< hardware_interface::StateInterface > on_export_state_interfaces() override
Definition pid_controller.cpp:373
controller_interface::InterfaceConfiguration state_interface_configuration() const override
Get configuration for controller's required state interfaces.
Definition pid_controller.cpp:324
std::vector< hardware_interface::CommandInterface > on_export_reference_interfaces() override
Definition pid_controller.cpp:349
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 pid_controller.cpp:429
controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition pid_controller.cpp:75
controller_interface::InterfaceConfiguration command_interface_configuration() const override
Get configuration for controller's required command interfaces.
Definition pid_controller.cpp:310
Definition realtime_publisher.hpp:55
Definition realtime_thread_safe_box.hpp:68
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:58