Skip to content

Commit

Permalink
configure service introspection via node options & parameters
Browse files Browse the repository at this point in the history
Signed-off-by: Brian Chen <[email protected]>
  • Loading branch information
ihasdapie authored and clalancette committed Feb 6, 2023
1 parent 1fd5a96 commit c26b4ae
Show file tree
Hide file tree
Showing 26 changed files with 988 additions and 57 deletions.
1 change: 1 addition & 0 deletions rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -78,6 +78,7 @@ set(${PROJECT_NAME}_SRCS
src/rclcpp/node_interfaces/node_logging.cpp
src/rclcpp/node_interfaces/node_parameters.cpp
src/rclcpp/node_interfaces/node_services.cpp
src/rclcpp/node_interfaces/node_service_introspection.cpp
src/rclcpp/node_interfaces/node_time_source.cpp
src/rclcpp/node_interfaces/node_timers.cpp
src/rclcpp/node_interfaces/node_topics.cpp
Expand Down
3 changes: 2 additions & 1 deletion rclcpp/include/rclcpp/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,14 +16,15 @@
#define RCLCPP__CLIENT_HPP_

#include <atomic>
#include <functional>
#include <future>
#include <unordered_map>
#include <memory>
#include <mutex>
#include <optional> // NOLINT, cpplint doesn't think this is a cpp std header
#include <sstream>
#include <string>
#include <tuple>
#include <unordered_map>
#include <utility>
#include <variant> // NOLINT
#include <vector>
Expand Down
42 changes: 35 additions & 7 deletions rclcpp/include/rclcpp/create_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <string>

#include "rclcpp/node_interfaces/node_base_interface.hpp"
#include "rclcpp/node_interfaces/node_clock_interface.hpp"
#include "rclcpp/node_interfaces/node_services_interface.hpp"
#include "rclcpp/qos.hpp"
#include "rmw/rmw.h"
Expand All @@ -44,15 +45,15 @@ create_client(
std::shared_ptr<node_interfaces::NodeBaseInterface> node_base,
std::shared_ptr<node_interfaces::NodeGraphInterface> node_graph,
std::shared_ptr<node_interfaces::NodeServicesInterface> node_services,
std::shared_ptr<node_interfaces::NodeClockInterface> node_clock,
const std::string & service_name,
const rclcpp::QoS & qos = rclcpp::ServicesQoS(),
rclcpp::CallbackGroup::SharedPtr group = nullptr)
const rclcpp::QoS & qos,
rclcpp::CallbackGroup::SharedPtr group,
bool enable_service_introspection)
{
return create_client<ServiceT>(
node_base, node_graph, node_services,
service_name,
qos.get_rmw_qos_profile(),
group);
node_base, node_graph, node_services, node_clock, service_name,
qos.get_rmw_qos_profile(), group, enable_service_introspection);
}

/// Create a service client with a given type.
Expand All @@ -63,12 +64,39 @@ create_client(
std::shared_ptr<node_interfaces::NodeBaseInterface> node_base,
std::shared_ptr<node_interfaces::NodeGraphInterface> node_graph,
std::shared_ptr<node_interfaces::NodeServicesInterface> node_services,
std::shared_ptr<node_interfaces::NodeClockInterface> node_clock,
const std::string & service_name,
const rmw_qos_profile_t & qos_profile,
rclcpp::CallbackGroup::SharedPtr group,
bool enable_service_introspection)
{
return create_client<ServiceT>(
node_base, node_graph, node_services, node_clock, service_name, qos_profile,
rcl_publisher_get_default_options().qos, group, enable_service_introspection);
}

/// Create a service client with a given type and qos profiles
/// \internal
template<typename ServiceT>
typename rclcpp::Client<ServiceT>::SharedPtr
create_client(
std::shared_ptr<node_interfaces::NodeBaseInterface> node_base,
std::shared_ptr<node_interfaces::NodeGraphInterface> node_graph,
std::shared_ptr<node_interfaces::NodeServicesInterface> node_services,
std::shared_ptr<node_interfaces::NodeClockInterface> node_clock,
const std::string & service_name,
const rmw_qos_profile_t & qos_profile,
rclcpp::CallbackGroup::SharedPtr group)
const rmw_qos_profile_t & service_event_publisher_qos_profile,
rclcpp::CallbackGroup::SharedPtr group,
bool enable_service_introspection)
{
rcl_client_options_t options = rcl_client_get_default_options();
options.qos = qos_profile;
if (enable_service_introspection) {
options.enable_service_introspection = enable_service_introspection;
options.clock = node_clock->get_clock()->get_clock_handle();
options.event_publisher_options.qos = service_event_publisher_qos_profile;
}

auto cli = rclcpp::Client<ServiceT>::make_shared(
node_base.get(),
Expand Down
43 changes: 38 additions & 5 deletions rclcpp/include/rclcpp/create_service.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include <utility>

#include "rclcpp/node_interfaces/node_base_interface.hpp"
#include "rclcpp/node_interfaces/node_clock_interface.hpp"
#include "rclcpp/node_interfaces/node_services_interface.hpp"
#include "rclcpp/visibility_control.hpp"
#include "rmw/rmw.h"
Expand All @@ -43,33 +44,65 @@ typename rclcpp::Service<ServiceT>::SharedPtr
create_service(
std::shared_ptr<node_interfaces::NodeBaseInterface> node_base,
std::shared_ptr<node_interfaces::NodeServicesInterface> node_services,
std::shared_ptr<node_interfaces::NodeClockInterface> node_clock,
const std::string & service_name,
CallbackT && callback,
const rclcpp::QoS & qos,
rclcpp::CallbackGroup::SharedPtr group)
rclcpp::CallbackGroup::SharedPtr group,
bool enable_service_introspection)
{
return create_service<ServiceT, CallbackT>(
node_base, node_services, service_name,
std::forward<CallbackT>(callback), qos.get_rmw_qos_profile(), group);
node_base, node_services, node_clock, service_name, std::forward<CallbackT>(callback),
qos.get_rmw_qos_profile(), group, enable_service_introspection);
}

/// Create a service with a given type.

/// Create a service with a given type
/// \internal
template<typename ServiceT, typename CallbackT>
typename rclcpp::Service<ServiceT>::SharedPtr
create_service(
std::shared_ptr<node_interfaces::NodeBaseInterface> node_base,
std::shared_ptr<node_interfaces::NodeServicesInterface> node_services,
std::shared_ptr<node_interfaces::NodeClockInterface> node_clock,
const std::string & service_name,
CallbackT && callback,
const rmw_qos_profile_t & qos_profile,
rclcpp::CallbackGroup::SharedPtr group,
bool enable_service_introspection
)
{
return create_service<ServiceT, CallbackT>(
node_base, node_services, node_clock, service_name, std::forward<CallbackT>(callback),
qos_profile, rcl_publisher_get_default_options().qos, group, enable_service_introspection);
}

/// Create a service with a given type and qos profiles
/// \internal
template<typename ServiceT, typename CallbackT>
typename rclcpp::Service<ServiceT>::SharedPtr
create_service(
std::shared_ptr<node_interfaces::NodeBaseInterface> node_base,
std::shared_ptr<node_interfaces::NodeServicesInterface> node_services,
std::shared_ptr<node_interfaces::NodeClockInterface> node_clock,
const std::string & service_name,
CallbackT && callback,
const rmw_qos_profile_t & qos_profile,
rclcpp::CallbackGroup::SharedPtr group)
const rmw_qos_profile_t & service_event_publisher_qos_profile,
rclcpp::CallbackGroup::SharedPtr group,
bool enable_service_introspection
)
{
rclcpp::AnyServiceCallback<ServiceT> any_service_callback;
any_service_callback.set(std::forward<CallbackT>(callback));

rcl_service_options_t service_options = rcl_service_get_default_options();
service_options.qos = qos_profile;
if (enable_service_introspection) {
service_options.enable_service_introspection = enable_service_introspection;
service_options.clock = node_clock->get_clock()->get_clock_handle();
service_options.event_publisher_options.qos = service_event_publisher_qos_profile;
}

auto serv = Service<ServiceT>::make_shared(
node_base->get_shared_rcl_node_handle(),
Expand Down
42 changes: 42 additions & 0 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,7 @@
#include "rclcpp/node_interfaces/node_logging_interface.hpp"
#include "rclcpp/node_interfaces/node_parameters_interface.hpp"
#include "rclcpp/node_interfaces/node_services_interface.hpp"
#include "rclcpp/node_interfaces/node_service_introspection_interface.hpp"
#include "rclcpp/node_interfaces/node_time_source_interface.hpp"
#include "rclcpp/node_interfaces/node_timers_interface.hpp"
#include "rclcpp/node_interfaces/node_topics_interface.hpp"
Expand Down Expand Up @@ -283,6 +284,22 @@ class Node : public std::enable_shared_from_this<Node>
const rclcpp::QoS & qos = rclcpp::ServicesQoS(),
rclcpp::CallbackGroup::SharedPtr group = nullptr);

/// Create and return a Client.
/**
* \param[in] service_name The name on which the service is accessible.
* \param[in] qos Quality of service profile for client.
* \param[in] service_event_publisher_qos QOS profile for the service event publisher.
* \param[in] group Callback group to handle the reply to service calls.
* \return Shared pointer to the created client.
*/
template<typename ServiceT>
typename Client<ServiceT>::SharedPtr
create_client(
const std::string & service_name,
const rclcpp::QoS & qos,
const rclcpp::QoS & service_event_publisher_qos,
rclcpp::CallbackGroup::SharedPtr group);

/// Create and return a Service.
/**
* \param[in] service_name The topic to service on.
Expand Down Expand Up @@ -317,6 +334,25 @@ class Node : public std::enable_shared_from_this<Node>
const rclcpp::QoS & qos = rclcpp::ServicesQoS(),
rclcpp::CallbackGroup::SharedPtr group = nullptr);


/// Create and return a Service.
/**
* \param[in] service_name The topic to service on.
* \param[in] callback User-defined callback function.
* \param[in] qos Quality of service profile for the service.
* \param[in] service_event_publisher_qos QOS profile for the service event publisher.
* \param[in] group Callback group to call the service.
* \return Shared pointer to the created service.
*/
template<typename ServiceT, typename CallbackT>
typename rclcpp::Service<ServiceT>::SharedPtr
create_service(
const std::string & service_name,
CallbackT && callback,
const rclcpp::QoS & qos,
const rclcpp::QoS & service_event_publisher_qos,
rclcpp::CallbackGroup::SharedPtr group);

/// Create and return a GenericPublisher.
/**
* The returned pointer will never be empty, but this function can throw various exceptions, for
Expand Down Expand Up @@ -1439,6 +1475,11 @@ class Node : public std::enable_shared_from_this<Node>
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr
get_node_services_interface();

/// Return the Node's internal NodeServicesInterface implementation.
RCLCPP_PUBLIC
rclcpp::node_interfaces::NodeServiceIntrospectionInterface::SharedPtr
get_node_service_introspection_interface();

/// Return the Node's internal NodeWaitablesInterface implementation.
RCLCPP_PUBLIC
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr
Expand Down Expand Up @@ -1587,6 +1628,7 @@ class Node : public std::enable_shared_from_this<Node>
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr node_time_source_;
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_;
rclcpp::node_interfaces::NodeServiceIntrospectionInterface::SharedPtr node_service_introspection_;

const rclcpp::NodeOptions node_options_;
const std::string sub_namespace_;
Expand Down
84 changes: 76 additions & 8 deletions rclcpp/include/rclcpp/node_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -143,13 +143,41 @@ Node::create_client(
const rclcpp::QoS & qos,
rclcpp::CallbackGroup::SharedPtr group)
{
return rclcpp::create_client<ServiceT>(
typename Client<ServiceT>::SharedPtr cli = rclcpp::create_client<ServiceT>(
node_base_,
node_graph_,
node_services_,
node_clock_,
extend_name_with_sub_namespace(service_name, this->get_sub_namespace()),
qos,
group);
group,
node_options_.enable_service_introspection());

node_service_introspection_->register_client(cli);
return cli;
}

template<typename ServiceT>
typename Client<ServiceT>::SharedPtr
Node::create_client(
const std::string & service_name,
const rclcpp::QoS & qos,
const rclcpp::QoS & service_event_publisher_qos,
rclcpp::CallbackGroup::SharedPtr group)
{
typename Client<ServiceT>::SharedPtr cli = rclcpp::create_client<ServiceT>(
node_base_,
node_graph_,
node_services_,
node_clock_,
extend_name_with_sub_namespace(service_name, this->get_sub_namespace()),
qos.get_rmw_qos_profile(),
service_event_publisher_qos.get_rmw_qos_profile(),
group,
node_options_.enable_service_introspection());

node_service_introspection_->register_client(cli);
return cli;
}

template<typename ServiceT>
Expand All @@ -159,13 +187,18 @@ Node::create_client(
const rmw_qos_profile_t & qos_profile,
rclcpp::CallbackGroup::SharedPtr group)
{
return rclcpp::create_client<ServiceT>(
typename Client<ServiceT>::SharedPtr cli = rclcpp::create_client<ServiceT>(
node_base_,
node_graph_,
node_services_,
node_clock_,
extend_name_with_sub_namespace(service_name, this->get_sub_namespace()),
qos_profile,
group);
group,
node_options_.enable_service_introspection());

node_service_introspection_->register_client(cli);
return cli;
}

template<typename ServiceT, typename CallbackT>
Expand All @@ -176,13 +209,42 @@ Node::create_service(
const rclcpp::QoS & qos,
rclcpp::CallbackGroup::SharedPtr group)
{
return rclcpp::create_service<ServiceT, CallbackT>(
typename rclcpp::Service<ServiceT>::SharedPtr serv = rclcpp::create_service<ServiceT, CallbackT>(
node_base_,
node_services_,
node_clock_,
extend_name_with_sub_namespace(service_name, this->get_sub_namespace()),
std::forward<CallbackT>(callback),
qos,
group);
group,
node_options_.enable_service_introspection());

node_service_introspection_->register_service(serv);
return serv;
}

template<typename ServiceT, typename CallbackT>
typename rclcpp::Service<ServiceT>::SharedPtr
Node::create_service(
const std::string & service_name,
CallbackT && callback,
const rclcpp::QoS & qos,
const rclcpp::QoS & service_event_publisher_qos,
rclcpp::CallbackGroup::SharedPtr group)
{
typename rclcpp::Service<ServiceT>::SharedPtr serv = rclcpp::create_service<ServiceT, CallbackT>(
node_base_,
node_services_,
node_clock_,
extend_name_with_sub_namespace(service_name, this->get_sub_namespace()),
std::forward<CallbackT>(callback),
qos.get_rmw_qos_profile(),
service_event_publisher_qos.get_rmw_qos_profile(),
group,
node_options_.enable_service_introspection());

node_service_introspection_->register_service(serv);
return serv;
}

template<typename ServiceT, typename CallbackT>
Expand All @@ -193,13 +255,19 @@ Node::create_service(
const rmw_qos_profile_t & qos_profile,
rclcpp::CallbackGroup::SharedPtr group)
{
return rclcpp::create_service<ServiceT, CallbackT>(
typename rclcpp::Service<ServiceT>::SharedPtr serv = rclcpp::create_service<ServiceT, CallbackT>(
node_base_,
node_services_,
node_clock_,
extend_name_with_sub_namespace(service_name, this->get_sub_namespace()),
std::forward<CallbackT>(callback),
qos_profile,
group);
group,
node_options_.enable_service_introspection()
);

node_service_introspection_->register_service(serv);
return serv;
}

template<typename AllocatorT>
Expand Down
3 changes: 2 additions & 1 deletion rclcpp/include/rclcpp/node_interfaces/node_parameters.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,8 @@ class NodeParameters : public NodeParametersInterface
const rclcpp::QoS & parameter_event_qos,
const rclcpp::PublisherOptionsBase & parameter_event_publisher_options,
bool allow_undeclared_parameters,
bool automatically_declare_parameters_from_overrides);
bool automatically_declare_parameters_from_overrides,
bool enable_service_introspection_for_parameter_service);

RCLCPP_PUBLIC
virtual
Expand Down
Loading

0 comments on commit c26b4ae

Please sign in to comment.