Skip to content

Commit aa85eb3

Browse files
committed
Add new interfaces to enable intropsection for action
Signed-off-by: Barry Xu <[email protected]>
1 parent f6b80ab commit aa85eb3

File tree

6 files changed

+135
-2
lines changed

6 files changed

+135
-2
lines changed

rclcpp_action/include/rclcpp_action/client.hpp

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -30,11 +30,13 @@
3030
#include "rcl/event_callback.h"
3131

3232
#include "rclcpp/exceptions.hpp"
33+
#include "rclcpp/clock.hpp"
3334
#include "rclcpp/macros.hpp"
3435
#include "rclcpp/node_interfaces/node_base_interface.hpp"
3536
#include "rclcpp/node_interfaces/node_logging_interface.hpp"
3637
#include "rclcpp/node_interfaces/node_graph_interface.hpp"
3738
#include "rclcpp/logger.hpp"
39+
#include "rclcpp/qos.hpp"
3840
#include "rclcpp/time.hpp"
3941
#include "rclcpp/waitable.hpp"
4042

@@ -187,6 +189,22 @@ class ClientBase : public rclcpp::Waitable
187189
// End Waitables API
188190
// -----------------
189191

192+
/// Configure action client introspection.
193+
/**
194+
* \param[in] clock clock to use to generate introspection timestamps
195+
* \param[in] qos_service_event_pub QoS settings to use when creating the introspection publisher
196+
* \param[in] introspection_state the state to set introspection to
197+
*
198+
* \throws std::invalid_argument if clock is nullptr
199+
* \throws rclcpp::exceptions::throw_from_rcl_error if rcl error occurs.
200+
*/
201+
RCLCPP_ACTION_PUBLIC
202+
void
203+
configure_introspection(
204+
rclcpp::Clock::SharedPtr clock,
205+
const rclcpp::QoS & qos_service_event_pub,
206+
rcl_service_introspection_state_t introspection_state);
207+
190208
protected:
191209
RCLCPP_ACTION_PUBLIC
192210
ClientBase(

rclcpp_action/include/rclcpp_action/server.hpp

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -28,9 +28,11 @@
2828
#include "rcl_action/action_server.h"
2929
#include "rosidl_runtime_c/action_type_support_struct.h"
3030
#include "rosidl_typesupport_cpp/action_type_support.hpp"
31+
#include "rclcpp/clock.hpp"
3132
#include "rclcpp/node_interfaces/node_base_interface.hpp"
3233
#include "rclcpp/node_interfaces/node_clock_interface.hpp"
3334
#include "rclcpp/node_interfaces/node_logging_interface.hpp"
35+
#include "rclcpp/qos.hpp"
3436
#include "rclcpp/waitable.hpp"
3537

3638
#include "rclcpp_action/visibility_control.hpp"
@@ -187,6 +189,22 @@ class ServerBase : public rclcpp::Waitable
187189
// End Waitables API
188190
// -----------------
189191

192+
/// Configure action server introspection
193+
/**
194+
* \param[in] clock clock to use to generate introspection timestamps
195+
* \param[in] qos_service_event_pub QoS settings to use when creating the introspection publisher
196+
* \param[in] introspection_state the state to set introspection to
197+
*
198+
* \throw std::invalid_argument if clock is nullptr
199+
* \throw rclcpp::exceptions::throw_from_rcl_error if rcl error occurs.
200+
*/
201+
RCLCPP_ACTION_PUBLIC
202+
void
203+
configure_introspection(
204+
rclcpp::Clock::SharedPtr clock,
205+
const rclcpp::QoS & qos_service_event_pub,
206+
rcl_service_introspection_state_t introspection_state);
207+
190208
protected:
191209
RCLCPP_ACTION_PUBLIC
192210
ServerBase(

rclcpp_action/src/client.cpp

Lines changed: 29 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -105,6 +105,7 @@ class ClientBaseImpl
105105
const rcl_action_client_options_t & client_options)
106106
: node_graph_(node_graph),
107107
node_handle(node_base->get_shared_rcl_node_handle()),
108+
action_type_support_(type_support),
108109
logger(node_logging->get_logger().get_child("rclcpp_action")),
109110
random_bytes_generator(std::random_device{}())
110111
{
@@ -167,6 +168,7 @@ class ClientBaseImpl
167168
// node_handle must be destroyed after client_handle to prevent memory leak
168169
std::shared_ptr<rcl_node_t> node_handle{nullptr};
169170
std::shared_ptr<rcl_action_client_t> client_handle{nullptr};
171+
const rosidl_action_type_support_t * action_type_support_;
170172
rclcpp::Logger logger;
171173

172174
using ResponseCallback = std::function<void (std::shared_ptr<void> response)>;
@@ -803,4 +805,31 @@ ClientBase::execute(const std::shared_ptr<void> & data_in)
803805
}, data_ptr->data);
804806
}
805807

808+
void
809+
ClientBase::configure_introspection(
810+
rclcpp::Clock::SharedPtr clock,
811+
const rclcpp::QoS & qos_service_event_pub,
812+
rcl_service_introspection_state_t introspection_state)
813+
{
814+
rcl_publisher_options_t pub_opts = rcl_publisher_get_default_options();
815+
pub_opts.qos = qos_service_event_pub.get_rmw_qos_profile();
816+
817+
if (clock == nullptr) {
818+
throw std::invalid_argument("clock is nullptr");
819+
}
820+
821+
rcl_ret_t ret = rcl_action_client_configure_internal_service_introspection(
822+
pimpl_->client_handle.get(),
823+
pimpl_->node_handle.get(),
824+
clock->get_clock_handle(),
825+
pimpl_->action_type_support_,
826+
pub_opts,
827+
introspection_state);
828+
829+
if (RCL_RET_OK != ret) {
830+
rclcpp::exceptions::throw_from_rcl_error(
831+
ret, "failed to configure action client introspection");
832+
}
833+
}
834+
806835
} // namespace rclcpp_action

rclcpp_action/src/server.cpp

Lines changed: 38 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -74,16 +74,25 @@ class ServerBaseImpl
7474
{
7575
public:
7676
ServerBaseImpl(
77+
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
78+
const rosidl_action_type_support_t * type_support,
7779
rclcpp::Clock::SharedPtr clock,
7880
rclcpp::Logger logger
7981
)
80-
: clock_(clock), logger_(logger)
82+
: node_handle_(node_base->get_shared_rcl_node_handle()),
83+
action_type_support_(type_support),
84+
clock_(clock),
85+
logger_(logger)
8186
{
8287
}
8388

8489
// Lock for action_server_
8590
std::recursive_mutex action_server_reentrant_mutex_;
8691

92+
std::shared_ptr<rcl_node_t> node_handle_;
93+
94+
const rosidl_action_type_support_t * action_type_support_;
95+
8796
rclcpp::Clock::SharedPtr clock_;
8897

8998
rclcpp::TimerBase::SharedPtr expire_timer_;
@@ -124,7 +133,8 @@ ServerBase::ServerBase(
124133
const rcl_action_server_options_t & options
125134
)
126135
: pimpl_(new ServerBaseImpl(
127-
node_clock->get_clock(), node_logging->get_logger().get_child("rclcpp_action")))
136+
node_base, type_support, node_clock->get_clock(),
137+
node_logging->get_logger().get_child("rclcpp_action")))
128138
{
129139
auto deleter = [node_base](rcl_action_server_t * ptr)
130140
{
@@ -929,3 +939,29 @@ ServerBase::get_timers() const
929939
{
930940
return {pimpl_->expire_timer_};
931941
}
942+
943+
void
944+
ServerBase::configure_introspection(
945+
rclcpp::Clock::SharedPtr clock, const rclcpp::QoS & qos_service_event_pub,
946+
rcl_service_introspection_state_t introspection_state)
947+
{
948+
rcl_publisher_options_t pub_opts = rcl_publisher_get_default_options();
949+
pub_opts.qos = qos_service_event_pub.get_rmw_qos_profile();
950+
951+
if (clock == nullptr) {
952+
throw std::invalid_argument("clock is nullptr");
953+
}
954+
955+
rcl_ret_t ret = rcl_action_server_configure_internal_service_introspection(
956+
pimpl_->action_server_.get(),
957+
pimpl_->node_handle_.get(),
958+
clock->get_clock_handle(),
959+
pimpl_->action_type_support_,
960+
pub_opts,
961+
introspection_state);
962+
963+
if (RCL_RET_OK != ret) {
964+
rclcpp::exceptions::throw_from_rcl_error(
965+
ret, "failed to configure action server introspection");
966+
}
967+
}

rclcpp_action/test/test_client.cpp

Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1037,3 +1037,20 @@ TEST_F(TestClientAgainstServer, execute_rcl_errors)
10371037
rclcpp::exceptions::RCLError);
10381038
}
10391039
}
1040+
1041+
TEST_F(TestClientAgainstServer, test_configure_introspection)
1042+
{
1043+
auto action_client = rclcpp_action::create_client<ActionType>(client_node, action_name);
1044+
1045+
EXPECT_THROW(
1046+
action_client->configure_introspection(
1047+
nullptr, rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS),
1048+
std::invalid_argument);
1049+
1050+
EXPECT_NO_THROW(
1051+
action_client->configure_introspection(
1052+
client_node->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS));
1053+
1054+
// No method was found to make rcl_action_client_configure_internal_service_introspection return
1055+
// a value other than RCL_RET_OK. mocking_utils::patch_and_return does not work for this function.
1056+
}

rclcpp_action/test/test_server.cpp

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1073,6 +1073,21 @@ class TestBasicServer : public TestServer
10731073
std::shared_ptr<GoalHandle> goal_handle_;
10741074
};
10751075

1076+
TEST_F(TestBasicServer, test_configure_introspection)
1077+
{
1078+
EXPECT_THROW(
1079+
action_server_->configure_introspection(
1080+
nullptr, rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS),
1081+
std::invalid_argument);
1082+
1083+
EXPECT_NO_THROW(
1084+
action_server_->configure_introspection(
1085+
node_->get_clock(), rclcpp::SystemDefaultsQoS(), RCL_SERVICE_INTROSPECTION_CONTENTS));
1086+
1087+
// No method was found to make rcl_action_server_configure_internal_service_introspection return
1088+
// a value other than RCL_RET_OK. mocking_utils::patch_and_return does not work for this function.
1089+
}
1090+
10761091
class TestGoalRequestServer : public TestBasicServer {};
10771092

10781093
TEST_F(TestGoalRequestServer, execute_goal_request_received_take_goal)

0 commit comments

Comments
 (0)