Skip to content

Commit 3f155e8

Browse files
committed
Add the missing visibility control macros
Signed-off-by: Barry Xu <[email protected]>
1 parent 9f366f0 commit 3f155e8

File tree

3 files changed

+19
-1
lines changed

3 files changed

+19
-1
lines changed

rclcpp_action/include/rclcpp_action/create_generic_client.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,7 @@ namespace rclcpp_action
3737
* \param[in] options Options to pass to the underlying `rcl_action_client_t`.
3838
* \return newly created generic client.
3939
*/
40+
RCLCPP_ACTION_PUBLIC
4041
typename GenericClient::SharedPtr
4142
create_generic_client(
4243
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,

rclcpp_action/include/rclcpp_action/generic_client.hpp

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -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

rclcpp_action/include/rclcpp_action/generic_client_goal_handle.hpp

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -67,25 +67,32 @@ class GenericClientGoalHandle
6767
const void *)>;
6868
using ResultCallback = std::function<void (const WrappedResult & result)>;
6969

70-
virtual ~GenericClientGoalHandle();
70+
RCLCPP_ACTION_PUBLIC
71+
virtual
72+
~GenericClientGoalHandle();
7173

7274
/// Get the unique ID for the goal.
75+
RCLCPP_ACTION_PUBLIC
7376
const GoalUUID &
7477
get_goal_id() const;
7578

7679
/// Get the time when the goal was accepted.
80+
RCLCPP_ACTION_PUBLIC
7781
rclcpp::Time
7882
get_goal_stamp() const;
7983

8084
/// Get the goal status code.
85+
RCLCPP_ACTION_PUBLIC
8186
int8_t
8287
get_status();
8388

8489
/// Check if an action client has subscribed to feedback for the goal.
90+
RCLCPP_ACTION_PUBLIC
8591
bool
8692
is_feedback_aware();
8793

8894
/// Check if an action client has requested the result for the goal.
95+
RCLCPP_ACTION_PUBLIC
8996
bool
9097
is_result_aware();
9198

0 commit comments

Comments
 (0)