Skip to content

Commit 9db7659

Browse files
Implement action generic client (#2759)
Signed-off-by: Barry Xu <[email protected]>
1 parent 48a4761 commit 9db7659

File tree

11 files changed

+2817
-285
lines changed

11 files changed

+2817
-285
lines changed

rclcpp_action/CMakeLists.txt

Lines changed: 18 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,10 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
2323
endif()
2424

2525
add_library(${PROJECT_NAME}
26-
src/client.cpp
26+
src/client_base.cpp
27+
src/create_generic_client.cpp
28+
src/generic_client.cpp
29+
src/generic_client_goal_handle.cpp
2730
src/qos.cpp
2831
src/server.cpp
2932
src/server_goal_handle.cpp
@@ -93,6 +96,20 @@ if(BUILD_TESTING)
9396
)
9497
endif()
9598

99+
ament_add_gtest(test_generic_client test/test_generic_client.cpp TIMEOUT 180)
100+
ament_add_test_label(test_generic_client mimick)
101+
if(TARGET test_generic_client)
102+
target_link_libraries(test_generic_client
103+
${PROJECT_NAME}
104+
mimick
105+
rcl::rcl
106+
rcl_action::rcl_action
107+
rclcpp::rclcpp
108+
rcutils::rcutils
109+
${test_msgs_TARGETS}
110+
)
111+
endif()
112+
96113
ament_add_gtest(test_server test/test_server.cpp TIMEOUT 180)
97114
ament_add_test_label(test_server mimick)
98115
if(TARGET test_server)

rclcpp_action/include/rclcpp_action/client.hpp

Lines changed: 1 addition & 281 deletions
Original file line numberDiff line numberDiff line change
@@ -41,294 +41,14 @@
4141
#include "rosidl_runtime_c/action_type_support_struct.h"
4242
#include "rosidl_typesupport_cpp/action_type_support.hpp"
4343

44+
#include "rclcpp_action/client_base.hpp"
4445
#include "rclcpp_action/client_goal_handle.hpp"
4546
#include "rclcpp_action/exceptions.hpp"
4647
#include "rclcpp_action/types.hpp"
4748
#include "rclcpp_action/visibility_control.hpp"
4849

49-
5050
namespace rclcpp_action
5151
{
52-
// Forward declaration
53-
class ClientBaseImpl;
54-
55-
/// Base Action Client implementation
56-
/// \internal
57-
/**
58-
* This class should not be used directly by users wanting to create an aciton client.
59-
* Instead users should use `rclcpp_action::Client<>`.
60-
*
61-
* Internally, this class is responsible for interfacing with the `rcl_action` API.
62-
*/
63-
class ClientBase : public rclcpp::Waitable
64-
{
65-
public:
66-
RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(ClientBase)
67-
68-
RCLCPP_ACTION_PUBLIC
69-
virtual ~ClientBase();
70-
71-
/// Enum to identify entities belonging to the action client
72-
enum class EntityType : std::size_t
73-
{
74-
GoalClient,
75-
ResultClient,
76-
CancelClient,
77-
FeedbackSubscription,
78-
StatusSubscription,
79-
};
80-
81-
/// Return true if there is an action server that is ready to take goal requests.
82-
RCLCPP_ACTION_PUBLIC
83-
bool
84-
action_server_is_ready() const;
85-
86-
/// Wait for action_server_is_ready() to become true, or until the given timeout is reached.
87-
template<typename RepT = int64_t, typename RatioT = std::milli>
88-
bool
89-
wait_for_action_server(
90-
std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
91-
{
92-
return wait_for_action_server_nanoseconds(
93-
std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
94-
);
95-
}
96-
97-
// -------------
98-
// Waitables API
99-
100-
/// \internal
101-
RCLCPP_ACTION_PUBLIC
102-
size_t
103-
get_number_of_ready_subscriptions() override;
104-
105-
/// \internal
106-
RCLCPP_ACTION_PUBLIC
107-
size_t
108-
get_number_of_ready_timers() override;
109-
110-
/// \internal
111-
RCLCPP_ACTION_PUBLIC
112-
size_t
113-
get_number_of_ready_clients() override;
114-
115-
/// \internal
116-
RCLCPP_ACTION_PUBLIC
117-
size_t
118-
get_number_of_ready_services() override;
119-
120-
/// \internal
121-
RCLCPP_ACTION_PUBLIC
122-
size_t
123-
get_number_of_ready_guard_conditions() override;
124-
125-
/// \internal
126-
RCLCPP_ACTION_PUBLIC
127-
void
128-
add_to_wait_set(rcl_wait_set_t & wait_set) override;
129-
130-
/// \internal
131-
RCLCPP_ACTION_PUBLIC
132-
bool
133-
is_ready(const rcl_wait_set_t & wait_set) override;
134-
135-
/// \internal
136-
RCLCPP_ACTION_PUBLIC
137-
std::shared_ptr<void>
138-
take_data() override;
139-
140-
/// \internal
141-
RCLCPP_ACTION_PUBLIC
142-
std::shared_ptr<void>
143-
take_data_by_entity_id(size_t id) override;
144-
145-
/// \internal
146-
RCLCPP_ACTION_PUBLIC
147-
void
148-
execute(const std::shared_ptr<void> & data) override;
149-
150-
/// \internal
151-
/// Set a callback to be called when action client entities have an event
152-
/**
153-
* The callback receives a size_t which is the number of messages received
154-
* since the last time this callback was called.
155-
* Normally this is 1, but can be > 1 if messages were received before any
156-
* callback was set.
157-
*
158-
* The callback also receives an int identifier argument, which identifies
159-
* the action client entity which is ready.
160-
* This implies that the provided callback can use the identifier to behave
161-
* differently depending on which entity triggered the waitable to become ready.
162-
*
163-
* Calling it again will clear any previously set callback.
164-
*
165-
* An exception will be thrown if the callback is not callable.
166-
*
167-
* This function is thread-safe.
168-
*
169-
* If you want more information available in the callback, like the subscription
170-
* or other information, you may use a lambda with captures or std::bind.
171-
*
172-
* \param[in] callback functor to be called when a new message is received.
173-
*/
174-
RCLCPP_ACTION_PUBLIC
175-
void
176-
set_on_ready_callback(std::function<void(size_t, int)> callback) override;
177-
178-
/// Unset the callback registered for new events, if any.
179-
RCLCPP_ACTION_PUBLIC
180-
void
181-
clear_on_ready_callback() override;
182-
183-
RCLCPP_ACTION_PUBLIC
184-
std::vector<std::shared_ptr<rclcpp::TimerBase>>
185-
get_timers() const override;
186-
187-
// End Waitables API
188-
// -----------------
189-
190-
protected:
191-
RCLCPP_ACTION_PUBLIC
192-
ClientBase(
193-
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
194-
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph,
195-
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging,
196-
const std::string & action_name,
197-
const rosidl_action_type_support_t * type_support,
198-
const rcl_action_client_options_t & options);
199-
200-
/// Wait for action_server_is_ready() to become true, or until the given timeout is reached.
201-
RCLCPP_ACTION_PUBLIC
202-
bool
203-
wait_for_action_server_nanoseconds(std::chrono::nanoseconds timeout);
204-
205-
// -----------------------------------------------------
206-
// API for communication between ClientBase and Client<>
207-
using ResponseCallback = std::function<void (std::shared_ptr<void> response)>;
208-
209-
/// \internal
210-
RCLCPP_ACTION_PUBLIC
211-
rclcpp::Logger get_logger();
212-
213-
/// \internal
214-
RCLCPP_ACTION_PUBLIC
215-
virtual
216-
GoalUUID
217-
generate_goal_id();
218-
219-
/// \internal
220-
RCLCPP_ACTION_PUBLIC
221-
virtual
222-
void
223-
send_goal_request(
224-
std::shared_ptr<void> request,
225-
ResponseCallback callback);
226-
227-
/// \internal
228-
RCLCPP_ACTION_PUBLIC
229-
virtual
230-
void
231-
send_result_request(
232-
std::shared_ptr<void> request,
233-
ResponseCallback callback);
234-
235-
/// \internal
236-
RCLCPP_ACTION_PUBLIC
237-
virtual
238-
void
239-
send_cancel_request(
240-
std::shared_ptr<void> request,
241-
ResponseCallback callback);
242-
243-
/// \internal
244-
virtual
245-
std::shared_ptr<void>
246-
create_goal_response() const = 0;
247-
248-
/// \internal
249-
RCLCPP_ACTION_PUBLIC
250-
virtual
251-
void
252-
handle_goal_response(
253-
const rmw_request_id_t & response_header,
254-
std::shared_ptr<void> goal_response);
255-
256-
/// \internal
257-
virtual
258-
std::shared_ptr<void>
259-
create_result_response() const = 0;
260-
261-
/// \internal
262-
RCLCPP_ACTION_PUBLIC
263-
virtual
264-
void
265-
handle_result_response(
266-
const rmw_request_id_t & response_header,
267-
std::shared_ptr<void> result_response);
268-
269-
/// \internal
270-
virtual
271-
std::shared_ptr<void>
272-
create_cancel_response() const = 0;
273-
274-
/// \internal
275-
RCLCPP_ACTION_PUBLIC
276-
virtual
277-
void
278-
handle_cancel_response(
279-
const rmw_request_id_t & response_header,
280-
std::shared_ptr<void> cancel_response);
281-
282-
/// \internal
283-
virtual
284-
std::shared_ptr<void>
285-
create_feedback_message() const = 0;
286-
287-
/// \internal
288-
virtual
289-
void
290-
handle_feedback_message(std::shared_ptr<void> message) = 0;
291-
292-
/// \internal
293-
virtual
294-
std::shared_ptr<void>
295-
create_status_message() const = 0;
296-
297-
/// \internal
298-
virtual
299-
void
300-
handle_status_message(std::shared_ptr<void> message) = 0;
301-
302-
// End API for communication between ClientBase and Client<>
303-
// ---------------------------------------------------------
304-
305-
/// \internal
306-
/// Set a callback to be called when the specified entity is ready
307-
RCLCPP_ACTION_PUBLIC
308-
void
309-
set_on_ready_callback(
310-
EntityType entity_type,
311-
rcl_event_callback_t callback,
312-
const void * user_data);
313-
314-
// Mutex to protect the callbacks storage.
315-
std::recursive_mutex listener_mutex_;
316-
// Storage for std::function callbacks to keep them in scope
317-
std::unordered_map<EntityType, std::function<void(size_t)>> entity_type_to_on_ready_callback_;
318-
319-
private:
320-
std::unique_ptr<ClientBaseImpl> pimpl_;
321-
322-
/// Set a std::function callback to be called when the specified entity is ready
323-
RCLCPP_ACTION_PUBLIC
324-
void
325-
set_callback_to_entity(
326-
EntityType entity_type,
327-
std::function<void(size_t, int)> callback);
328-
329-
bool on_ready_callback_set_{false};
330-
};
331-
33252
/// Action Client
33353
/**
33454
* This class creates an action client.

0 commit comments

Comments
 (0)