ros2_control - jazzy
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 <memory>
22#include <string>
23#include <vector>
24
25#include "control_msgs/msg/multi_dof_command.hpp"
26#include "control_msgs/msg/multi_dof_state_stamped.hpp"
27#include "control_toolbox/pid_ros.hpp"
28#include "controller_interface/chainable_controller_interface.hpp"
29#include "rclcpp_lifecycle/state.hpp"
30#include "realtime_tools/realtime_buffer.hpp"
31#include "realtime_tools/realtime_publisher.hpp"
32#include "std_srvs/srv/set_bool.hpp"
33
34#include "pid_controller/pid_controller_parameters.hpp"
35
36namespace pid_controller
37{
38
40{
41public:
43
44 controller_interface::CallbackReturn on_init() override;
45
47
49
50 controller_interface::CallbackReturn on_cleanup(
51 const rclcpp_lifecycle::State & previous_state) override;
52
53 controller_interface::CallbackReturn on_configure(
54 const rclcpp_lifecycle::State & previous_state) override;
55
56 controller_interface::CallbackReturn on_activate(
57 const rclcpp_lifecycle::State & previous_state) override;
58
59 controller_interface::return_type update_reference_from_subscribers(
60 const rclcpp::Time & time, const rclcpp::Duration & period) override;
61
62 controller_interface::return_type update_and_write_commands(
63 const rclcpp::Time & time, const rclcpp::Duration & period) override;
64
65 using ControllerReferenceMsg = control_msgs::msg::MultiDOFCommand;
66 using ControllerMeasuredStateMsg = control_msgs::msg::MultiDOFCommand;
67 using ControllerModeSrvType = std_srvs::srv::SetBool;
68 using ControllerStateMsg = control_msgs::msg::MultiDOFStateStamped;
69
70protected:
71 std::shared_ptr<pid_controller::ParamListener> param_listener_;
72 pid_controller::Params params_;
73
74 std::vector<std::string> reference_and_state_dof_names_;
75 size_t dof_;
76 std::vector<double> measured_state_values_;
77
78 using PidPtr = std::shared_ptr<control_toolbox::PidROS>;
79 std::vector<PidPtr> pids_;
80 // Feed-forward velocity weight factor when calculating closed loop pid adapter's command
81 std::vector<double> feedforward_gain_;
82
83 // Command subscribers and Controller State publisher
84 rclcpp::Subscription<ControllerReferenceMsg>::SharedPtr ref_subscriber_ = nullptr;
86
87 rclcpp::Subscription<ControllerMeasuredStateMsg>::SharedPtr measured_state_subscriber_ = nullptr;
89
90 rclcpp::Service<ControllerModeSrvType>::SharedPtr set_feedforward_control_service_;
91 realtime_tools::RealtimeBuffer<bool> feedforward_mode_enabled_;
92
94
95 rclcpp::Publisher<ControllerStateMsg>::SharedPtr s_publisher_;
96 std::unique_ptr<ControllerStatePublisher> state_publisher_;
97
98 // override methods from ChainableControllerInterface
99 std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces() override;
100
101 std::vector<hardware_interface::StateInterface> on_export_state_interfaces() override;
102
103 bool on_set_chained_mode(bool chained_mode) override;
104
105 // internal methods
106 void update_parameters();
107 controller_interface::CallbackReturn configure_parameters();
108
109private:
110 // callback for topic interface
111 void reference_callback(const std::shared_ptr<ControllerReferenceMsg> msg);
112};
113
114} // namespace pid_controller
115
116#endif // PID_CONTROLLER__PID_CONTROLLER_HPP_
Definition chainable_controller_interface.hpp:37
Definition pid_controller.hpp:40
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:473
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:429
std::vector< hardware_interface::StateInterface > on_export_state_interfaces() override
Definition pid_controller.cpp:406
controller_interface::InterfaceConfiguration state_interface_configuration() const override
Get configuration for controller's required state interfaces.
Definition pid_controller.cpp:357
std::vector< hardware_interface::CommandInterface > on_export_reference_interfaces() override
Definition pid_controller.cpp:382
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:452
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:343
Definition realtime_buffer.hpp:44
Definition realtime_publisher.hpp:55
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:58