Skip to content

Commit 97d0d5c

Browse files
committed
add expand_action_name APIs to action client and server
Signed-off-by: Alberto Soragna <[email protected]>
1 parent 6da8363 commit 97d0d5c

File tree

6 files changed

+120
-0
lines changed

6 files changed

+120
-0
lines changed

rclcpp_action/include/rclcpp_action/client.hpp

+6
Original file line numberDiff line numberDiff line change
@@ -91,6 +91,12 @@ class ClientBase : public rclcpp::Waitable
9191
);
9292
}
9393

94+
/// Compute the name of the action by expanding the namespace.
95+
/** \return The name of the action. */
96+
RCLCPP_ACTION_PUBLIC
97+
std::string
98+
expand_action_name() const;
99+
94100
// -------------
95101
// Waitables API
96102

rclcpp_action/include/rclcpp_action/server.hpp

+6
Original file line numberDiff line numberDiff line change
@@ -84,6 +84,12 @@ class ServerBase : public rclcpp::Waitable
8484
RCLCPP_ACTION_PUBLIC
8585
virtual ~ServerBase();
8686

87+
/// Compute the name of the action by expanding the namespace.
88+
/** \return The name of the action. */
89+
RCLCPP_ACTION_PUBLIC
90+
std::string
91+
expand_action_name() const;
92+
8793
// -------------
8894
// Waitables API
8995

rclcpp_action/src/client.cpp

+21
Original file line numberDiff line numberDiff line change
@@ -222,6 +222,27 @@ ClientBase::action_server_is_ready() const
222222
return is_ready;
223223
}
224224

225+
std::string
226+
ClientBase::expand_action_name() const
227+
{
228+
char * output_cstr = NULL;
229+
auto allocator = rcl_get_default_allocator();
230+
// Call `rcl_node_resolve_name with `only_expand` mode: remapping action names is not supported
231+
rcl_ret_t ret = rcl_node_resolve_name(
232+
this->pimpl_->node_handle.get(),
233+
rcl_action_client_get_action_name(this->pimpl_->client_handle.get()),
234+
allocator,
235+
/*is_service*/ true,
236+
/*only_expand*/ true,
237+
&output_cstr);
238+
if (RCL_RET_OK != ret) {
239+
rclcpp::exceptions::throw_from_rcl_error(ret, "failed to resolve name", rcl_get_error_state());
240+
}
241+
std::string output{output_cstr};
242+
allocator.deallocate(output_cstr, allocator.state);
243+
return output;
244+
}
245+
225246
bool
226247
ClientBase::wait_for_action_server_nanoseconds(std::chrono::nanoseconds timeout)
227248
{

rclcpp_action/src/server.cpp

+24
Original file line numberDiff line numberDiff line change
@@ -86,6 +86,8 @@ class ServerBaseImpl
8686

8787
rclcpp::Clock::SharedPtr clock_;
8888

89+
// node_handle_ must be destroyed after client_handle to prevent memory leak
90+
std::shared_ptr<rcl_node_t> node_handle_{nullptr};
8991
// Do not declare this before clock_ as this depends on clock_(see #1526)
9092
std::shared_ptr<rcl_action_server_t> action_server_;
9193

@@ -138,6 +140,7 @@ ServerBase::ServerBase(
138140
}
139141
};
140142

143+
pimpl_->node_handle_ = node_base->get_shared_rcl_node_handle();
141144
pimpl_->action_server_.reset(new rcl_action_server_t, deleter);
142145
*(pimpl_->action_server_) = rcl_action_get_zero_initialized_server();
143146

@@ -168,6 +171,27 @@ ServerBase::~ServerBase()
168171
{
169172
}
170173

174+
std::string
175+
ServerBase::expand_action_name() const
176+
{
177+
char * output_cstr = NULL;
178+
auto allocator = rcl_get_default_allocator();
179+
// Call `rcl_node_resolve_name with `only_expand` mode: remapping action names is not supported
180+
rcl_ret_t ret = rcl_node_resolve_name(
181+
this->pimpl_->node_handle_.get(),
182+
rcl_action_server_get_action_name(this->pimpl_->action_server_.get()),
183+
allocator,
184+
/*is_service*/ true,
185+
/*only_expand*/ true,
186+
&output_cstr);
187+
if (RCL_RET_OK != ret) {
188+
rclcpp::exceptions::throw_from_rcl_error(ret, "failed to resolve name", rcl_get_error_state());
189+
}
190+
std::string output{output_cstr};
191+
allocator.deallocate(output_cstr, allocator.state);
192+
return output;
193+
}
194+
171195
size_t
172196
ServerBase::get_number_of_ready_subscriptions()
173197
{

rclcpp_action/test/test_client.cpp

+24
Original file line numberDiff line numberDiff line change
@@ -389,6 +389,30 @@ TEST_F(TestClient, wait_for_action_server_rcl_errors)
389389
TearDownServer();
390390
}
391391

392+
TEST_F(TestClient, action_name)
393+
{
394+
{
395+
// Default namespace
396+
auto test_node = std::make_shared<rclcpp::Node>("test_node");
397+
auto action_client = rclcpp_action::create_client<ActionType>(test_node, "my_action");
398+
EXPECT_EQ(action_client->expand_action_name(), "/my_action");
399+
}
400+
401+
{
402+
// Custom namespace
403+
auto test_node = std::make_shared<rclcpp::Node>("test_node", "test_namespace");
404+
auto action_client = rclcpp_action::create_client<ActionType>(test_node, "my_action");
405+
EXPECT_EQ(action_client->expand_action_name(), "/test_namespace/my_action");
406+
}
407+
408+
{
409+
// Action with absolute (global) name
410+
auto test_node = std::make_shared<rclcpp::Node>("test_node", "test_namespace");
411+
auto action_client = rclcpp_action::create_client<ActionType>(test_node, "/my_action");
412+
EXPECT_EQ(action_client->expand_action_name(), "/my_action");
413+
}
414+
}
415+
392416
TEST_F(TestClient, is_ready) {
393417
auto action_client = rclcpp_action::create_client<ActionType>(client_node, action_name);
394418
rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();

rclcpp_action/test/test_server.cpp

+39
Original file line numberDiff line numberDiff line change
@@ -226,6 +226,45 @@ TEST_F(TestServer, construction_and_destruction_sub_node)
226226
});
227227
}
228228

229+
TEST_F(TestServer, action_name)
230+
{
231+
auto create_server_func = [](std::shared_ptr<rclcpp::Node> node, const std::string & action_name)
232+
{
233+
using GoalHandle = rclcpp_action::ServerGoalHandle<Fibonacci>;
234+
auto as = rclcpp_action::create_server<Fibonacci>(
235+
node, action_name,
236+
[](const GoalUUID &, std::shared_ptr<const Fibonacci::Goal>) {
237+
return rclcpp_action::GoalResponse::REJECT;
238+
},
239+
[](std::shared_ptr<GoalHandle>) {
240+
return rclcpp_action::CancelResponse::REJECT;
241+
},
242+
[](std::shared_ptr<GoalHandle>) {});
243+
return as;
244+
};
245+
246+
{
247+
// Default namespace
248+
auto test_node = std::make_shared<rclcpp::Node>("test_node");
249+
auto action_server = create_server_func(test_node, "my_action");
250+
EXPECT_EQ(action_server->expand_action_name(), "/my_action");
251+
}
252+
253+
{
254+
// Custom namespace
255+
auto test_node = std::make_shared<rclcpp::Node>("test_node", "test_namespace");
256+
auto action_server = create_server_func(test_node, "my_action");
257+
EXPECT_EQ(action_server->expand_action_name(), "/test_namespace/my_action");
258+
}
259+
260+
{
261+
// Action with absolute (global) name
262+
auto test_node = std::make_shared<rclcpp::Node>("test_node", "test_namespace");
263+
auto action_server = create_server_func(test_node, "/my_action");
264+
EXPECT_EQ(action_server->expand_action_name(), "/my_action");
265+
}
266+
}
267+
229268
TEST_F(TestServer, handle_goal_called)
230269
{
231270
auto node = std::make_shared<rclcpp::Node>("handle_goal_node", "/rclcpp_action/handle_goal");

0 commit comments

Comments
 (0)