ros2_control - rolling
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 "pid_controller/visibility_control.h"
30 #include "pid_controller_parameters.hpp"
31 #include "rclcpp_lifecycle/state.hpp"
32 #include "realtime_tools/realtime_buffer.hpp"
33 #include "realtime_tools/realtime_publisher.hpp"
34 #include "std_srvs/srv/set_bool.hpp"
35 
36 namespace pid_controller
37 {
38 
39 enum class feedforward_mode_type : std::uint8_t
40 {
41  OFF = 0,
42  ON = 1,
43 };
44 
46 {
47 public:
48  PID_CONTROLLER__VISIBILITY_PUBLIC
49  PidController();
50 
51  PID_CONTROLLER__VISIBILITY_PUBLIC
52  controller_interface::CallbackReturn on_init() override;
53 
54  PID_CONTROLLER__VISIBILITY_PUBLIC
56 
57  PID_CONTROLLER__VISIBILITY_PUBLIC
59 
60  PID_CONTROLLER__VISIBILITY_PUBLIC
61  controller_interface::CallbackReturn on_cleanup(
62  const rclcpp_lifecycle::State & previous_state) override;
63 
64  PID_CONTROLLER__VISIBILITY_PUBLIC
65  controller_interface::CallbackReturn on_configure(
66  const rclcpp_lifecycle::State & previous_state) override;
67 
68  PID_CONTROLLER__VISIBILITY_PUBLIC
69  controller_interface::CallbackReturn on_activate(
70  const rclcpp_lifecycle::State & previous_state) override;
71 
72  PID_CONTROLLER__VISIBILITY_PUBLIC
73  controller_interface::CallbackReturn on_deactivate(
74  const rclcpp_lifecycle::State & previous_state) override;
75 
76  PID_CONTROLLER__VISIBILITY_PUBLIC
77  controller_interface::return_type update_reference_from_subscribers(
78  const rclcpp::Time & time, const rclcpp::Duration & period) override;
79 
80  PID_CONTROLLER__VISIBILITY_PUBLIC
81  controller_interface::return_type update_and_write_commands(
82  const rclcpp::Time & time, const rclcpp::Duration & period) override;
83 
84  using ControllerReferenceMsg = control_msgs::msg::MultiDOFCommand;
85  using ControllerMeasuredStateMsg = control_msgs::msg::MultiDOFCommand;
86  using ControllerModeSrvType = std_srvs::srv::SetBool;
87  using ControllerStateMsg = control_msgs::msg::MultiDOFStateStamped;
88 
89 protected:
90  std::shared_ptr<pid_controller::ParamListener> param_listener_;
91  pid_controller::Params params_;
92 
93  std::vector<std::string> reference_and_state_dof_names_;
94  size_t dof_;
95  std::vector<double> measured_state_values_;
96 
97  using PidPtr = std::shared_ptr<control_toolbox::PidROS>;
98  std::vector<PidPtr> pids_;
99  // Feed-forward velocity weight factor when calculating closed loop pid adapter's command
100  std::vector<double> feedforward_gain_;
101 
102  // Command subscribers and Controller State publisher
103  rclcpp::Subscription<ControllerReferenceMsg>::SharedPtr ref_subscriber_ = nullptr;
105 
106  rclcpp::Subscription<ControllerMeasuredStateMsg>::SharedPtr measured_state_subscriber_ = nullptr;
108 
109  rclcpp::Service<ControllerModeSrvType>::SharedPtr set_feedforward_control_service_;
111 
113 
114  rclcpp::Publisher<ControllerStateMsg>::SharedPtr s_publisher_;
115  std::unique_ptr<ControllerStatePublisher> state_publisher_;
116 
117  // override methods from ChainableControllerInterface
118  std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces() override;
119 
120  std::vector<hardware_interface::StateInterface> on_export_state_interfaces() override;
121 
122  bool on_set_chained_mode(bool chained_mode) override;
123 
124  // internal methods
125  void update_parameters();
126  controller_interface::CallbackReturn configure_parameters();
127 
128 private:
129  // callback for topic interface
130  PID_CONTROLLER__VISIBILITY_LOCAL
131  void reference_callback(const std::shared_ptr<ControllerReferenceMsg> msg);
132 };
133 
134 } // namespace pid_controller
135 
136 #endif // PID_CONTROLLER__PID_CONTROLLER_HPP_
Definition: chainable_controller_interface.hpp:38
Definition: pid_controller.hpp:46
PID_CONTROLLER__VISIBILITY_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: 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:424
std::vector< hardware_interface::StateInterface > on_export_state_interfaces() override
Definition: pid_controller.cpp:403
PID_CONTROLLER__VISIBILITY_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration() const override
Get configuration for controller's required state interfaces.
Definition: pid_controller.cpp:356
std::vector< hardware_interface::CommandInterface > on_export_reference_interfaces() override
Definition: pid_controller.cpp:381
PID_CONTROLLER__VISIBILITY_PUBLIC 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
PID_CONTROLLER__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition: pid_controller.cpp:75
PID_CONTROLLER__VISIBILITY_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration() const override
Get configuration for controller's required command interfaces.
Definition: pid_controller.cpp:342
Definition: realtime_buffer.hpp:44
Definition: realtime_publisher.hpp:54
Configuring what command/state interfaces to claim.
Definition: controller_interface_base.hpp:58