@@ -104,6 +104,7 @@ class GenericClient : public ClientBase
104104 * \param[in] action_typesupport_handle the action type support handle
105105 * \param[in] client_options Options to pass to the underlying `rcl_action::rcl_action_client_t`.
106106 */
107+ RCLCPP_ACTION_PUBLIC
107108 GenericClient (
108109 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
109110 rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph,
@@ -139,6 +140,7 @@ class GenericClient : public ClientBase
139140 * \return A future that completes when the goal has been accepted or rejected.
140141 * If the goal is rejected, then the result will be a `nullptr`.
141142 */
143+ RCLCPP_ACTION_PUBLIC
142144 std::shared_future<typename GenericClientGoalHandle::SharedPtr>
143145 async_send_goal (
144146 const Goal goal,
@@ -153,6 +155,7 @@ class GenericClient : public ClientBase
153155 * \return A future that completes when the goal has been accepted or rejected.
154156 * If the goal is rejected, then the result will be a `nullptr`.
155157 */
158+ RCLCPP_ACTION_PUBLIC
156159 std::shared_future<typename GenericClientGoalHandle::SharedPtr>
157160 async_send_goal (
158161 const GoalRequest goal_request,
@@ -166,6 +169,7 @@ class GenericClient : public ClientBase
166169 * \param[in] result_callback Optional callback that is called when the result is received.
167170 * \return A future that is set to the goal result when the goal is finished.
168171 */
172+ RCLCPP_ACTION_PUBLIC
169173 std::shared_future<WrappedResult>
170174 async_get_result (
171175 typename GenericClientGoalHandle::SharedPtr goal_handle,
@@ -184,6 +188,7 @@ class GenericClient : public ClientBase
184188 * <a href="https://github.com/ros2/rcl_interfaces/blob/master/action_msgs/srv/CancelGoal.srv">
185189 * action_msgs/CancelGoal.srv</a>.
186190 */
191+ RCLCPP_ACTION_PUBLIC
187192 std::shared_future<typename CancelResponse::SharedPtr>
188193 async_cancel_goal (
189194 typename GenericClientGoalHandle::SharedPtr goal_handle,
@@ -199,6 +204,7 @@ class GenericClient : public ClientBase
199204 * <a href="https://github.com/ros2/rcl_interfaces/blob/master/action_msgs/srv/CancelGoal.srv">
200205 * action_msgs/CancelGoal.srv</a>.
201206 */
207+ RCLCPP_ACTION_PUBLIC
202208 std::shared_future<typename CancelResponse::SharedPtr>
203209 async_cancel_all_goals (CancelCallback cancel_callback = nullptr );
204210
@@ -213,13 +219,15 @@ class GenericClient : public ClientBase
213219 *
214220 * \param[in] goal_handle The goal were the callbacks shall be stopped
215221 */
222+ RCLCPP_ACTION_PUBLIC
216223 void
217224 stop_callbacks (typename GenericClientGoalHandle::SharedPtr goal_handle);
218225
219226 // / Stops the callbacks for the goal in a thread safe way
220227 /* *
221228 * For further information see stop_callbacks(typename GenericGoalHandle::SharedPtr goal_handle)
222229 */
230+ RCLCPP_ACTION_PUBLIC
223231 void
224232 stop_callbacks (const GoalUUID & goal_id);
225233
@@ -234,11 +242,13 @@ class GenericClient : public ClientBase
234242 * <a href="https://github.com/ros2/rcl_interfaces/blob/master/action_msgs/srv/CancelGoal.srv">
235243 * action_msgs/CancelGoal.srv</a>.
236244 */
245+ RCLCPP_ACTION_PUBLIC
237246 std::shared_future<typename CancelResponse::SharedPtr>
238247 async_cancel_goals_before (
239248 const rclcpp::Time & stamp,
240249 CancelCallback cancel_callback = nullptr );
241250
251+ RCLCPP_ACTION_PUBLIC
242252 virtual
243253 ~GenericClient ();
244254
0 commit comments