Skip to content

Commit 680cf79

Browse files
committed
Introduce get client and server info by service
Signed-off-by: Minju, Lee <[email protected]>
1 parent 1e95407 commit 680cf79

File tree

9 files changed

+586
-1
lines changed

9 files changed

+586
-1
lines changed

rclcpp/include/rclcpp/node.hpp

Lines changed: 60 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1388,6 +1388,66 @@ class Node : public std::enable_shared_from_this<Node>
13881388
std::vector<rclcpp::TopicEndpointInfo>
13891389
get_subscriptions_info_by_topic(const std::string & topic_name, bool no_mangle = false) const;
13901390

1391+
/// Return the service endpoint information about clients on a given service.
1392+
/**
1393+
* The returned parameter is a list of service endpoint information, where each item will contain
1394+
* the node name, node namespace, service type, endpoint type, endpoint count,
1395+
* service endpoint's GIDs, and its QoS profiles.
1396+
*
1397+
* When the `no_mangle` parameter is `true`, the provided `service_name` should be a valid service
1398+
* name for the middleware (useful when combining ROS with native middleware apps).
1399+
* When the `no_mangle` parameter is `false`, the provided `service_name` should follow
1400+
* ROS service name conventions. In DDS-based RMWs, services are implemented as topics with mangled
1401+
* names (e.g., `rq/my_serviceRequest` and `rp/my_serviceReply`), so `no_mangle = true` is not
1402+
* supported and will result in an error. Use `get_publishers_info_by_topic` or
1403+
* `get_subscriptions_info_by_topic` for unmangled topic queries in such cases. Other RMWs
1404+
* (e.g., Zenoh) may support `no_mangle = true` if they natively handle services without topic-based
1405+
*
1406+
* 'service_name` may be a relative, private, or fully qualified service name.
1407+
* A relative or private service will be expanded using this node's namespace and name.
1408+
* The queried `service_name` is not remapped.
1409+
*
1410+
* \param[in] service_name the actual service name used; it will not be automatically remapped.
1411+
* \param[in] no_mangle if `true`, `service_name` needs to be a valid middleware service name,
1412+
* otherwise it should be a valid ROS service name. Defaults to `false`.
1413+
* \return a list of SeviceEndpointInfo representing all the clients on this service.
1414+
* \throws InvalidServiceNameError if the given service_name is invalid.
1415+
* \throws std::runtime_error if internal error happens.
1416+
*/
1417+
RCLCPP_PUBLIC
1418+
std::vector<rclcpp::ServiceEndpointInfo>
1419+
get_clients_info_by_service(const std::string & service_name, bool no_mangle = false) const;
1420+
1421+
/// Return the service endpoint information about servers on a given service.
1422+
/**
1423+
* The returned parameter is a list of service endpoint information, where each item will contain
1424+
* the node name, node namespace, service type, endpoint type, endpoint count,
1425+
* service endpoint's GIDs, and its QoS profiles.
1426+
*
1427+
* When the `no_mangle` parameter is `true`, the provided `service_name` should be a valid service
1428+
* name for the middleware (useful when combining ROS with native middleware apps).
1429+
* When the `no_mangle` parameter is `false`, the provided `service_name` should follow
1430+
* ROS service name conventions. In DDS-based RMWs, services are implemented as topics with mangled
1431+
* names (e.g., `rq/my_serviceRequest` and `rp/my_serviceReply`), so `no_mangle = true` is not
1432+
* supported and will result in an error. Use `rcl_get_publishers_info_by_topic` or
1433+
* `rcl_get_subscriptions_info_by_topic` for unmangled topic queries in such cases. Other RMWs
1434+
* (e.g., Zenoh) may support `no_mangle = true` if they natively handle services without topic-based
1435+
*
1436+
* 'service_name` may be a relative, private, or fully qualified service name.
1437+
* A relative or private service will be expanded using this node's namespace and name.
1438+
* The queried `service_name` is not remapped.
1439+
*
1440+
* \param[in] service_name the actual service name used; it will not be automatically remapped.
1441+
* \param[in] no_mangle if `true`, `service_name` needs to be a valid middleware service name,
1442+
* otherwise it should be a valid ROS service name. Defaults to `false`.
1443+
* \return a list of SeviceEndpointInfo representing all the servers on this service.
1444+
* \throws InvalidServiceNameError if the given service_name is invalid.
1445+
* \throws std::runtime_error if internal error happens.
1446+
*/
1447+
RCLCPP_PUBLIC
1448+
std::vector<rclcpp::ServiceEndpointInfo>
1449+
get_servers_info_by_service(const std::string & service_name, bool no_mangle = false) const;
1450+
13911451
/// Return a graph event, which will be set anytime a graph change occurs.
13921452
/* The graph Event object is a loan which must be returned.
13931453
* The Event object is scoped and therefore to return the loan just let it go

rclcpp/include/rclcpp/node_interfaces/node_graph.hpp

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,7 @@
3333
#include "rclcpp/node_interfaces/node_base_interface.hpp"
3434
#include "rclcpp/node_interfaces/node_graph_interface.hpp"
3535
#include "rclcpp/visibility_control.hpp"
36+
#include "rmw/service_endpoint_info_array.h"
3637
#include "rmw/topic_endpoint_info_array.h"
3738

3839
namespace rclcpp
@@ -159,6 +160,18 @@ class NodeGraph : public NodeGraphInterface
159160
const std::string & topic_name,
160161
bool no_mangle = false) const override;
161162

163+
RCLCPP_PUBLIC
164+
std::vector<rclcpp::ServiceEndpointInfo>
165+
get_clients_info_by_service(
166+
const std::string & service_name,
167+
bool no_mangle = false) const override;
168+
169+
RCLCPP_PUBLIC
170+
std::vector<rclcpp::ServiceEndpointInfo>
171+
get_servers_info_by_service(
172+
const std::string & service_name,
173+
bool no_mangle = false) const override;
174+
162175
private:
163176
RCLCPP_DISABLE_COPY(NodeGraph)
164177

rclcpp/include/rclcpp/node_interfaces/node_graph_interface.hpp

Lines changed: 146 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,9 @@ enum class EndpointType
4040
{
4141
Invalid = RMW_ENDPOINT_INVALID,
4242
Publisher = RMW_ENDPOINT_PUBLISHER,
43-
Subscription = RMW_ENDPOINT_SUBSCRIPTION
43+
Subscription = RMW_ENDPOINT_SUBSCRIPTION,
44+
Client = RMW_ENDPOINT_CLIENT,
45+
Server = RMW_ENDPOINT_SERVER
4446
};
4547

4648
/**
@@ -143,6 +145,125 @@ class TopicEndpointInfo
143145
rosidl_type_hash_t topic_type_hash_;
144146
};
145147

148+
/**
149+
* Struct that contains service endpoint information like the associated node name, node namespace,
150+
* service type, endpoint type, endpoint count, endpoint GIDs, and its QoS profiles.
151+
*/
152+
class ServiceEndpointInfo
153+
{
154+
public:
155+
/// Construct a ServiceEndpointInfo from a rcl_service_endpoint_info_t.
156+
RCLCPP_PUBLIC
157+
explicit ServiceEndpointInfo(const rcl_service_endpoint_info_t & info)
158+
: node_name_(info.node_name),
159+
node_namespace_(info.node_namespace),
160+
service_type_(info.service_type),
161+
endpoint_type_(static_cast<rclcpp::EndpointType>(info.endpoint_type)),
162+
service_type_hash_(info.service_type_hash),
163+
endpoint_count_(info.endpoint_count)
164+
{
165+
for(size_t i = 0; i < endpoint_count_; i++) {
166+
std::array<uint8_t, RMW_GID_STORAGE_SIZE> gid;
167+
std::copy(info.endpoint_gids[i], info.endpoint_gids[i] + RMW_GID_STORAGE_SIZE, gid.begin());
168+
endpoint_gids_.push_back(gid);
169+
170+
rclcpp::QoS qos(
171+
{info.qos_profiles[i].history, info.qos_profiles[i].depth}, info.qos_profiles[i]);
172+
qos_profiles_.push_back(qos);
173+
}
174+
}
175+
176+
/// Get a mutable reference to the node name.
177+
RCLCPP_PUBLIC
178+
std::string &
179+
node_name();
180+
181+
/// Get a const reference to the node name.
182+
RCLCPP_PUBLIC
183+
const std::string &
184+
node_name() const;
185+
186+
/// Get a mutable reference to the node namespace.
187+
RCLCPP_PUBLIC
188+
std::string &
189+
node_namespace();
190+
191+
/// Get a const reference to the node namespace.
192+
RCLCPP_PUBLIC
193+
const std::string &
194+
node_namespace() const;
195+
196+
/// Get a mutable reference to the service type string.
197+
RCLCPP_PUBLIC
198+
std::string &
199+
service_type();
200+
201+
/// Get a const reference to the service type string.
202+
RCLCPP_PUBLIC
203+
const std::string &
204+
service_type() const;
205+
206+
/// Get a mutable reference to the service endpoint type.
207+
RCLCPP_PUBLIC
208+
rclcpp::EndpointType &
209+
endpoint_type();
210+
211+
/// Get a const reference to the service endpoint type.
212+
RCLCPP_PUBLIC
213+
const rclcpp::EndpointType &
214+
endpoint_type() const;
215+
216+
/// Get a mutable reference to the endpoint count.
217+
RCLCPP_PUBLIC
218+
size_t &
219+
endpoint_count();
220+
221+
/// Get a const reference to the endpoint count.
222+
RCLCPP_PUBLIC
223+
const size_t &
224+
endpoint_count() const;
225+
226+
/// Get a mutable reference to the GID of the service endpoint.
227+
RCLCPP_PUBLIC
228+
std::vector<std::array<uint8_t, RMW_GID_STORAGE_SIZE>> &
229+
endpoint_gids();
230+
231+
/// Get a const reference to the GID of the service endpoint.
232+
RCLCPP_PUBLIC
233+
const std::vector<std::array<uint8_t, RMW_GID_STORAGE_SIZE>> &
234+
endpoint_gids() const;
235+
236+
/// Get a mutable reference to the QoS profile of the service endpoint.
237+
RCLCPP_PUBLIC
238+
std::vector<rclcpp::QoS> &
239+
qos_profiles();
240+
241+
/// Get a const reference to the QoS profile of the service endpoint.
242+
RCLCPP_PUBLIC
243+
const std::vector<rclcpp::QoS> &
244+
qos_profiles() const;
245+
246+
/// Get a mutable reference to the type hash of the service endpoint.
247+
RCLCPP_PUBLIC
248+
rosidl_type_hash_t &
249+
service_type_hash();
250+
251+
/// Get a const reference to the type hash of the service endpoint.
252+
RCLCPP_PUBLIC
253+
const rosidl_type_hash_t &
254+
service_type_hash() const;
255+
256+
private:
257+
std::string node_name_;
258+
std::string node_namespace_;
259+
std::string service_type_;
260+
rclcpp::EndpointType endpoint_type_;
261+
std::vector<std::array<uint8_t, RMW_GID_STORAGE_SIZE>> endpoint_gids_;
262+
std::vector<rclcpp::QoS> qos_profiles_;
263+
rosidl_type_hash_t service_type_hash_;
264+
size_t endpoint_count_;
265+
};
266+
146267
namespace node_interfaces
147268
{
148269

@@ -408,6 +529,30 @@ class NodeGraphInterface
408529
virtual
409530
std::vector<rclcpp::TopicEndpointInfo>
410531
get_subscriptions_info_by_topic(const std::string & topic_name, bool no_mangle = false) const = 0;
532+
533+
/// Return the service endpoint information about clients on a given service.
534+
/**
535+
* \param[in] service_name the actual service name used; it will not be automatically remapped.
536+
* \param[in] no_mangle if `true`, `service_name` needs to be a valid middleware service name,
537+
* otherwise it should be a valid ROS service name.
538+
* \sa rclcpp::Node::get_clients_info_by_service
539+
*/
540+
RCLCPP_PUBLIC
541+
virtual
542+
std::vector<rclcpp::ServiceEndpointInfo>
543+
get_clients_info_by_service(const std::string & service_name, bool no_mangle = false) const = 0;
544+
545+
/// Return the service endpoint information about servers on a given service.
546+
/**
547+
* \param[in] service_name the actual service name used; it will not be automatically remapped.
548+
* \param[in] no_mangle if `true`, `service_name` needs to be a valid middleware service name,
549+
* otherwise it should be a valid ROS service name.
550+
* \sa rclcpp::Node::get_servers_info_by_service
551+
*/
552+
RCLCPP_PUBLIC
553+
virtual
554+
std::vector<rclcpp::ServiceEndpointInfo>
555+
get_servers_info_by_service(const std::string & service_name, bool no_mangle = false) const = 0;
411556
};
412557

413558
} // namespace node_interfaces

rclcpp/src/rclcpp/node.cpp

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -547,6 +547,18 @@ Node::get_subscriptions_info_by_topic(const std::string & topic_name, bool no_ma
547547
return node_graph_->get_subscriptions_info_by_topic(topic_name, no_mangle);
548548
}
549549

550+
std::vector<rclcpp::ServiceEndpointInfo>
551+
Node::get_clients_info_by_service(const std::string & service_name, bool no_mangle) const
552+
{
553+
return node_graph_->get_clients_info_by_service(service_name, no_mangle);
554+
}
555+
556+
std::vector<rclcpp::ServiceEndpointInfo>
557+
Node::get_servers_info_by_service(const std::string & service_name, bool no_mangle) const
558+
{
559+
return node_graph_->get_servers_info_by_service(service_name, no_mangle);
560+
}
561+
550562
void
551563
Node::for_each_callback_group(
552564
const node_interfaces::NodeBaseInterface::CallbackGroupFunction & func)

0 commit comments

Comments
 (0)