2020#include < utility>
2121#include < vector>
2222
23- #include " controller_interface/visibility_control.h"
2423#include " realtime_tools/async_function_handler.hpp"
2524
2625#include " hardware_interface/handle.hpp"
@@ -98,10 +97,8 @@ struct ControllerUpdateStatus
9897class ControllerInterfaceBase : public rclcpp_lifecycle ::node_interfaces::LifecycleNodeInterface
9998{
10099public:
101- CONTROLLER_INTERFACE_PUBLIC
102100 ControllerInterfaceBase () = default ;
103101
104- CONTROLLER_INTERFACE_PUBLIC
105102 virtual ~ControllerInterfaceBase () = default ;
106103
107104 // / Get configuration for controller's required command interfaces.
@@ -116,7 +113,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
116113 *
117114 * \returns configuration of command interfaces.
118115 */
119- CONTROLLER_INTERFACE_PUBLIC
120116 virtual InterfaceConfiguration command_interface_configuration () const = 0;
121117
122118 // / Get configuration for controller's required state interfaces.
@@ -133,7 +129,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
133129 *
134130 * \returns configuration of state interfaces.
135131 */
136- CONTROLLER_INTERFACE_PUBLIC
137132 virtual InterfaceConfiguration state_interface_configuration () const = 0;
138133
139134 // / Method that assigns the Loaned interfaces to the controller.
@@ -145,7 +140,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
145140 * \param[in] command_interfaces vector of command interfaces to be assigned to the controller.
146141 * \param[in] state_interfaces vector of state interfaces to be assigned to the controller.
147142 */
148- CONTROLLER_INTERFACE_PUBLIC
149143 virtual void assign_interfaces (
150144 std::vector<hardware_interface::LoanedCommandInterface> && command_interfaces,
151145 std::vector<hardware_interface::LoanedStateInterface> && state_interfaces);
@@ -154,10 +148,8 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
154148 /* *
155149 * Method used by the controller_manager to release the interfaces from the controller.
156150 */
157- CONTROLLER_INTERFACE_PUBLIC
158151 virtual void release_interfaces ();
159152
160- CONTROLLER_INTERFACE_PUBLIC
161153 return_type init (
162154 const std::string & controller_name, const std::string & urdf, unsigned int cm_update_rate,
163155 const std::string & node_namespace, const rclcpp::NodeOptions & node_options);
@@ -166,11 +158,9 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
166158 /*
167159 * Override default implementation for configure of LifecycleNode to get parameters.
168160 */
169- CONTROLLER_INTERFACE_PUBLIC
170161 const rclcpp_lifecycle::State & configure ();
171162
172163 // / Extending interface with initialization method which is individual for each controller
173- CONTROLLER_INTERFACE_PUBLIC
174164 virtual CallbackReturn on_init () = 0;
175165
176166 /* *
@@ -182,7 +172,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
182172 * \param[in] period The measured time since the last control loop iteration
183173 * \returns return_type::OK if update is successfully, otherwise return_type::ERROR.
184174 */
185- CONTROLLER_INTERFACE_PUBLIC
186175 virtual return_type update (const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
187176
188177 /* *
@@ -197,25 +186,18 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
197186 * \returns ControllerUpdateStatus. The status contains information if the update was triggered
198187 * successfully, the result of the update method and the execution duration of the update method.
199188 */
200- CONTROLLER_INTERFACE_PUBLIC
201189 ControllerUpdateStatus trigger_update (const rclcpp::Time & time, const rclcpp::Duration & period);
202190
203- CONTROLLER_INTERFACE_PUBLIC
204191 std::shared_ptr<rclcpp_lifecycle::LifecycleNode> get_node ();
205192
206- CONTROLLER_INTERFACE_PUBLIC
207193 std::shared_ptr<const rclcpp_lifecycle::LifecycleNode> get_node () const ;
208194
209- CONTROLLER_INTERFACE_PUBLIC
210195 const rclcpp_lifecycle::State & get_lifecycle_state () const ;
211196
212- CONTROLLER_INTERFACE_PUBLIC
213197 unsigned int get_update_rate () const ;
214198
215- CONTROLLER_INTERFACE_PUBLIC
216199 bool is_async () const ;
217200
218- CONTROLLER_INTERFACE_PUBLIC
219201 const std::string & get_robot_description () const ;
220202
221203 /* *
@@ -229,7 +211,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
229211 *
230212 * @returns NodeOptions required for the configuration of the controller lifecycle node
231213 */
232- CONTROLLER_INTERFACE_PUBLIC
233214 virtual rclcpp::NodeOptions define_custom_node_options () const
234215 {
235216 rclcpp::NodeOptions node_options;
@@ -272,7 +253,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
272253 *
273254 * \returns true is controller is chainable and false if it is not.
274255 */
275- CONTROLLER_INTERFACE_PUBLIC
276256 virtual bool is_chainable () const = 0;
277257
278258 /* *
@@ -281,7 +261,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
281261 *
282262 * \returns list of command interfaces for preceding controllers.
283263 */
284- CONTROLLER_INTERFACE_PUBLIC
285264 virtual std::vector<hardware_interface::CommandInterface::SharedPtr>
286265 export_reference_interfaces () = 0 ;
287266
@@ -291,7 +270,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
291270 *
292271 * \returns list of state interfaces for preceding controllers.
293272 */
294- CONTROLLER_INTERFACE_PUBLIC
295273 virtual std::vector<hardware_interface::StateInterface::ConstSharedPtr>
296274 export_state_interfaces () = 0 ;
297275
@@ -303,7 +281,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
303281 *
304282 * \returns true if mode is switched successfully and false if not.
305283 */
306- CONTROLLER_INTERFACE_PUBLIC
307284 virtual bool set_chained_mode (bool chained_mode) = 0;
308285
309286 // / Get information if a controller is currently in chained mode.
@@ -314,7 +291,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
314291 *
315292 * \returns true is controller is in chained mode and false if it is not.
316293 */
317- CONTROLLER_INTERFACE_PUBLIC
318294 virtual bool is_in_chained_mode () const = 0;
319295
320296 /* *
@@ -327,7 +303,6 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
327303 * If the controller is running in async mode, the method will wait for the current async update
328304 * to finish. If the controller is not running in async mode, the method will do nothing.
329305 */
330- CONTROLLER_INTERFACE_PUBLIC
331306 void wait_for_trigger_update_to_finish ();
332307
333308protected:
0 commit comments