15#ifndef CONTROLLER_INTERFACE__CHAINABLE_CONTROLLER_INTERFACE_HPP_
16#define CONTROLLER_INTERFACE__CHAINABLE_CONTROLLER_INTERFACE_HPP_
20#include <unordered_map>
23#include "controller_interface/controller_interface_base.hpp"
24#include "hardware_interface/handle.hpp"
26namespace controller_interface
52 return_type
update(
const rclcpp::Time & time,
const rclcpp::Duration & period)
final;
109 const rclcpp::Time & time,
const rclcpp::Duration & period) = 0;
123 const rclcpp::Time & time,
const rclcpp::Duration & period) = 0;
127 std::vector<hardware_interface::StateInterface::SharedPtr> ordered_exported_state_interfaces_;
128 std::unordered_map<std::string, hardware_interface::StateInterface::SharedPtr>
129 exported_state_interfaces_;
131 std::vector<double> state_interfaces_values_;
137 std::vector<double> reference_interfaces_;
139 std::vector<hardware_interface::CommandInterface::SharedPtr>
140 ordered_exported_reference_interfaces_;
141 std::unordered_map<std::string, hardware_interface::CommandInterface::SharedPtr>
142 exported_reference_interfaces_;
146 bool in_chained_mode_ =
false;
Definition chainable_controller_interface.hpp:37
virtual return_type update_and_write_commands(const rclcpp::Time &time, const rclcpp::Duration &period)=0
Execute calculations of the controller and update command interfaces.
virtual return_type update_reference_from_subscribers(const rclcpp::Time &time, const rclcpp::Duration &period)=0
Update reference from input topics when not in chained mode.
virtual std::vector< hardware_interface::CommandInterface > on_export_reference_interfaces()
Definition chainable_controller_interface.cpp:237
std::vector< std::string > exported_reference_interface_names_
Storage of values for reference interfaces.
Definition chainable_controller_interface.hpp:135
virtual bool on_set_chained_mode(bool chained_mode)
Virtual method that each chainable controller should implement to switch chained mode.
Definition chainable_controller_interface.cpp:221
bool is_in_chained_mode() const final
Get information if a controller is currently in chained mode.
Definition chainable_controller_interface.cpp:219
return_type update(const rclcpp::Time &time, const rclcpp::Duration &period) final
Definition chainable_controller_interface.cpp:29
virtual std::vector< hardware_interface::StateInterface > on_export_state_interfaces()
Definition chainable_controller_interface.cpp:224
std::vector< std::string > exported_state_interface_names_
Storage of values for state interfaces.
Definition chainable_controller_interface.hpp:126
bool set_chained_mode(bool chained_mode) final
Definition chainable_controller_interface.cpp:193
bool is_chainable() const final
Get information if a controller is chainable.
Definition chainable_controller_interface.cpp:27
std::vector< hardware_interface::CommandInterface::SharedPtr > export_reference_interfaces() final
Definition chainable_controller_interface.cpp:113
std::vector< hardware_interface::StateInterface::ConstSharedPtr > export_state_interfaces() final
Definition chainable_controller_interface.cpp:49
Definition controller_interface_base.hpp:98