18#ifndef PID_CONTROLLER__PID_CONTROLLER_HPP_
19#define PID_CONTROLLER__PID_CONTROLLER_HPP_
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"
34#include "pid_controller/pid_controller_parameters.hpp"
36namespace pid_controller
39enum class feedforward_mode_type : std::uint8_t
50 controller_interface::CallbackReturn
on_init()
override;
56 controller_interface::CallbackReturn on_cleanup(
57 const rclcpp_lifecycle::State & previous_state)
override;
59 controller_interface::CallbackReturn on_configure(
60 const rclcpp_lifecycle::State & previous_state)
override;
62 controller_interface::CallbackReturn on_activate(
63 const rclcpp_lifecycle::State & previous_state)
override;
66 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
69 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
71 using ControllerReferenceMsg = control_msgs::msg::MultiDOFCommand;
72 using ControllerMeasuredStateMsg = control_msgs::msg::MultiDOFCommand;
73 using ControllerModeSrvType = std_srvs::srv::SetBool;
74 using ControllerStateMsg = control_msgs::msg::MultiDOFStateStamped;
77 std::shared_ptr<pid_controller::ParamListener> param_listener_;
78 pid_controller::Params params_;
80 std::vector<std::string> reference_and_state_dof_names_;
82 std::vector<double> measured_state_values_;
84 using PidPtr = std::shared_ptr<control_toolbox::PidROS>;
85 std::vector<PidPtr> pids_;
87 std::vector<double> feedforward_gain_;
90 rclcpp::Subscription<ControllerReferenceMsg>::SharedPtr ref_subscriber_ =
nullptr;
93 rclcpp::Subscription<ControllerMeasuredStateMsg>::SharedPtr measured_state_subscriber_ =
nullptr;
96 rclcpp::Service<ControllerModeSrvType>::SharedPtr set_feedforward_control_service_;
101 rclcpp::Publisher<ControllerStateMsg>::SharedPtr s_publisher_;
102 std::unique_ptr<ControllerStatePublisher> state_publisher_;
112 void update_parameters();
113 controller_interface::CallbackReturn configure_parameters();
117 void reference_callback(
const std::shared_ptr<ControllerReferenceMsg> msg);
Definition chainable_controller_interface.hpp:37
Definition pid_controller.hpp:46
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:467
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
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
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:446
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:342
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:57