69 CONTROLLER_INTERFACE_PUBLIC
72 CONTROLLER_INTERFACE_PUBLIC
87 CONTROLLER_INTERFACE_PUBLIC
104 CONTROLLER_INTERFACE_PUBLIC
107 CONTROLLER_INTERFACE_PUBLIC
108 void assign_interfaces(
109 std::vector<hardware_interface::LoanedCommandInterface> && command_interfaces,
110 std::vector<hardware_interface::LoanedStateInterface> && state_interfaces);
112 CONTROLLER_INTERFACE_PUBLIC
113 void release_interfaces();
115 CONTROLLER_INTERFACE_PUBLIC
116 virtual return_type init(
117 const std::string & controller_name,
const std::string & namespace_ =
"",
118 const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions().enable_logger_service(
true));
124 CONTROLLER_INTERFACE_PUBLIC
125 const rclcpp_lifecycle::State &
configure();
128 CONTROLLER_INTERFACE_PUBLIC
140 CONTROLLER_INTERFACE_PUBLIC
141 virtual return_type
update(
const rclcpp::Time & time,
const rclcpp::Duration & period) = 0;
143 CONTROLLER_INTERFACE_PUBLIC
144 std::shared_ptr<rclcpp_lifecycle::LifecycleNode> get_node();
146 CONTROLLER_INTERFACE_PUBLIC
147 std::shared_ptr<rclcpp_lifecycle::LifecycleNode> get_node()
const;
149 CONTROLLER_INTERFACE_PUBLIC
150 const rclcpp_lifecycle::State & get_state()
const;
152 CONTROLLER_INTERFACE_PUBLIC
153 unsigned int get_update_rate()
const;
155 CONTROLLER_INTERFACE_PUBLIC
156 bool is_async()
const;
165 template <
typename ParameterT>
166 auto auto_declare(
const std::string & name,
const ParameterT & default_value)
168 if (!node_->has_parameter(name))
170 return node_->declare_parameter<ParameterT>(name, default_value);
174 return node_->get_parameter(name).get_value<ParameterT>();
187 CONTROLLER_INTERFACE_PUBLIC
196 CONTROLLER_INTERFACE_PUBLIC
207 CONTROLLER_INTERFACE_PUBLIC
218 CONTROLLER_INTERFACE_PUBLIC
222 std::vector<hardware_interface::LoanedCommandInterface> command_interfaces_;
223 std::vector<hardware_interface::LoanedStateInterface> state_interfaces_;
224 unsigned int update_rate_ = 0;
225 bool is_async_ =
false;
228 std::shared_ptr<rclcpp_lifecycle::LifecycleNode> node_;
auto auto_declare(const std::string &name, const ParameterT &default_value)
Declare and initialize a parameter with a type.
Definition controller_interface_base.hpp:166