Class PidController

Inheritance Relationships

Base Type

  • public controller_interface::ChainableControllerInterface

Class Documentation

class PidController : public controller_interface::ChainableControllerInterface

Public Types

using ControllerReferenceMsg = control_msgs::msg::MultiDOFCommand
using ControllerMeasuredStateMsg = control_msgs::msg::MultiDOFCommand
using ControllerModeSrvType = std_srvs::srv::SetBool
using ControllerStateMsg = control_msgs::msg::MultiDOFStateStamped

Public Functions

PID_CONTROLLER__VISIBILITY_PUBLIC PidController()
PID_CONTROLLER__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_init () override
PID_CONTROLLER__VISIBILITY_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration () const override
PID_CONTROLLER__VISIBILITY_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration () const override
PID_CONTROLLER__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_cleanup (const rclcpp_lifecycle::State &previous_state) override
PID_CONTROLLER__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) override
PID_CONTROLLER__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override
PID_CONTROLLER__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override
PID_CONTROLLER__VISIBILITY_PUBLIC controller_interface::return_type update_and_write_commands (const rclcpp::Time &time, const rclcpp::Duration &period) override

Protected Types

using PidPtr = std::shared_ptr<control_toolbox::PidROS>
using ControllerStatePublisher = realtime_tools::RealtimePublisher<ControllerStateMsg>

Protected Functions

controller_interface::return_type update_reference_from_subscribers() override
std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces() override
bool on_set_chained_mode(bool chained_mode) override
void update_parameters()
controller_interface::CallbackReturn configure_parameters()

Protected Attributes

std::shared_ptr<pid_controller::ParamListener> param_listener_
pid_controller::Params params_
std::vector<std::string> reference_and_state_dof_names_
size_t dof_
std::vector<double> measured_state_values_
std::vector<PidPtr> pids_
std::vector<double> feedforward_gain_
rclcpp::Subscription<ControllerReferenceMsg>::SharedPtr ref_subscriber_ = nullptr
realtime_tools::RealtimeBuffer<std::shared_ptr<ControllerReferenceMsg>> input_ref_
rclcpp::Subscription<ControllerMeasuredStateMsg>::SharedPtr measured_state_subscriber_ = nullptr
realtime_tools::RealtimeBuffer<std::shared_ptr<ControllerMeasuredStateMsg>> measured_state_
rclcpp::Service<ControllerModeSrvType>::SharedPtr set_feedforward_control_service_
realtime_tools::RealtimeBuffer<feedforward_mode_type> control_mode_
rclcpp::Publisher<ControllerStateMsg>::SharedPtr s_publisher_
std::unique_ptr<ControllerStatePublisher> state_publisher_