54 PID_CONTROLLER__VISIBILITY_PUBLIC
57 PID_CONTROLLER__VISIBILITY_PUBLIC
58 controller_interface::CallbackReturn
on_init()
override;
60 PID_CONTROLLER__VISIBILITY_PUBLIC
63 PID_CONTROLLER__VISIBILITY_PUBLIC
66 PID_CONTROLLER__VISIBILITY_PUBLIC
67 controller_interface::CallbackReturn on_cleanup(
68 const rclcpp_lifecycle::State & previous_state)
override;
70 PID_CONTROLLER__VISIBILITY_PUBLIC
71 controller_interface::CallbackReturn on_configure(
72 const rclcpp_lifecycle::State & previous_state)
override;
74 PID_CONTROLLER__VISIBILITY_PUBLIC
75 controller_interface::CallbackReturn on_activate(
76 const rclcpp_lifecycle::State & previous_state)
override;
78 PID_CONTROLLER__VISIBILITY_PUBLIC
79 controller_interface::CallbackReturn on_deactivate(
80 const rclcpp_lifecycle::State & previous_state)
override;
82 PID_CONTROLLER__VISIBILITY_PUBLIC
84 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
86 PID_CONTROLLER__VISIBILITY_PUBLIC
88 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
90 using ControllerReferenceMsg = control_msgs::msg::MultiDOFCommand;
91 using ControllerMeasuredStateMsg = control_msgs::msg::MultiDOFCommand;
92 using ControllerModeSrvType = std_srvs::srv::SetBool;
93 using ControllerStateMsg = control_msgs::msg::MultiDOFStateStamped;
96 std::shared_ptr<pid_controller::ParamListener> param_listener_;
97 pid_controller::Params params_;
99 std::vector<std::string> reference_and_state_dof_names_;
101 std::vector<double> measured_state_values_;
103 using PidPtr = std::shared_ptr<control_toolbox::PidROS>;
104 std::vector<PidPtr> pids_;
106 std::vector<double> feedforward_gain_;
109 rclcpp::Subscription<ControllerReferenceMsg>::SharedPtr ref_subscriber_ =
nullptr;
112 rclcpp::Subscription<ControllerMeasuredStateMsg>::SharedPtr measured_state_subscriber_ =
nullptr;
115 rclcpp::Service<ControllerModeSrvType>::SharedPtr set_feedforward_control_service_;
120 rclcpp::Publisher<ControllerStateMsg>::SharedPtr s_publisher_;
121 std::unique_ptr<ControllerStatePublisher> state_publisher_;
129 void update_parameters();
130 controller_interface::CallbackReturn configure_parameters();
134 PID_CONTROLLER__VISIBILITY_LOCAL
135 void reference_callback(
const std::shared_ptr<ControllerReferenceMsg> msg);
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: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:307
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:382
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:63
PID_CONTROLLER__VISIBILITY_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration() const override
Get configuration for controller's required command interfaces.
Definition pid_controller.cpp:293