Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

add verbose in service-info verb #916

Open
wants to merge 1 commit into
base: rolling
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions ros2cli/ros2cli/daemon/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,9 @@ def serve(server: LocalXMLRPCServer, *, timeout: int = 2 * 60 * 60):
node.get_subscriber_names_and_types_by_node,
node.get_subscriptions_info_by_topic,
node.get_service_names_and_types_by_node,
node.get_servers_info_by_service,
node.get_client_names_and_types_by_node,
node.get_clients_info_by_service,
bind(rclpy.action.get_action_server_names_and_types_by_node, node),
bind(rclpy.action.get_action_client_names_and_types_by_node, node),
node.count_publishers,
Expand Down
49 changes: 48 additions & 1 deletion ros2cli/test/test_daemon.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@

import rclpy
import rclpy.action
from rclpy.topic_endpoint_info import TopicEndpointTypeEnum

from ros2cli.node.daemon import DaemonNode
from ros2cli.node.daemon import is_daemon_running
Expand All @@ -44,6 +45,16 @@
durability=rclpy.qos.DurabilityPolicy.VOLATILE,
depth=1
)
TEST_SRV_CLIENT_QOS = rclpy.qos.QoSProfile(
reliability=rclpy.qos.ReliabilityPolicy.RELIABLE,
durability=rclpy.qos.DurabilityPolicy.VOLATILE,
depth=1
)
TEST_SRV_SERVICE_QOS = rclpy.qos.QoSProfile(
reliability=rclpy.qos.ReliabilityPolicy.BEST_EFFORT,
durability=rclpy.qos.DurabilityPolicy.VOLATILE,
depth=1
)
TEST_SERVICE_NAME = '/test/service'
TEST_SERVICE_TYPE = 'test_msgs/srv/Empty'
TEST_ACTION_NAME = '/test/action'
Expand All @@ -70,11 +81,13 @@ def local_node():
service = node.create_service(
srv_type=test_msgs.srv.Empty,
srv_name=TEST_SERVICE_NAME,
qos_profile=TEST_SRV_SERVICE_QOS,
callback=(lambda req, res: res)
)
client = node.create_client(
srv_type=test_msgs.srv.Empty,
srv_name=TEST_SERVICE_NAME
srv_name=TEST_SERVICE_NAME,
qos_profile=TEST_SRV_CLIENT_QOS
)

def noop_execute_callback(goal_handle):
Expand Down Expand Up @@ -231,6 +244,40 @@ def test_get_subscriptions_info_by_topic(daemon_node):
TEST_TOPIC_SUBSCRIPTION_QOS.reliability


def test_get_clients_info_by_service(daemon_node):
clients_info = daemon_node.get_clients_info_by_service(TEST_SERVICE_NAME)
assert len(clients_info) >= 1
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

should be one that is only matching with the service? if that is correct, probably we do not need the following for statement either.

Suggested change
assert len(clients_info) >= 1
assert len(clients_info) == 1

for client_info in clients_info:
assert client_info.node_name == TEST_NODE_NAME
assert client_info.node_namespace == TEST_NODE_NAMESPACE
assert client_info.qos_profile.durability == \
TEST_SRV_CLIENT_QOS.durability
assert client_info.qos_profile.reliability == \
TEST_SRV_CLIENT_QOS.reliability
assert TEST_SERVICE_TYPE in client_info.topic_type
if TEST_SERVICE_TYPE + '_Request' == client_info.topic_type:
client_info.endpoint_type == TopicEndpointTypeEnum.PUBLISHER
elif TEST_SERVICE_TYPE + '_Response' == client_info.topic_type:
client_info.endpoint_type == TopicEndpointTypeEnum.SUBSCRIPTION


def test_get_servers_info_by_service(daemon_node):
servers_info = daemon_node.get_servers_info_by_service(TEST_SERVICE_NAME)
assert len(servers_info) >= 1
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

same here, should it be one?

Suggested change
assert len(servers_info) >= 1
assert len(servers_info) == 1

for server_info in servers_info:
assert server_info.node_name == TEST_NODE_NAME
assert server_info.node_namespace == TEST_NODE_NAMESPACE
assert server_info.qos_profile.durability == \
TEST_SRV_SERVICE_QOS.durability
assert server_info.qos_profile.reliability == \
TEST_SRV_SERVICE_QOS.reliability
assert TEST_SERVICE_TYPE in server_info.topic_type
if TEST_SERVICE_TYPE + '_Request' == server_info.topic_type:
server_info.endpoint_type == TopicEndpointTypeEnum.SUBSCRIPTION
elif TEST_SERVICE_TYPE + '_Response' == server_info.topic_type:
server_info.endpoint_type == TopicEndpointTypeEnum.PUBLISHER


def test_count_publishers(daemon_node):
assert 1 == daemon_node.count_publishers(TEST_TOPIC_NAME)

Expand Down
29 changes: 27 additions & 2 deletions ros2service/ros2service/verb/info.py
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,13 @@ def add_arguments(self, parser, cli_name):
arg = parser.add_argument(
'service_name',
help="Name of the ROS service to get info (e.g. '/add_two_ints')")
parser.add_argument(
'--verbose',
'-v',
action='store_true',
help='Prints detailed information like the node name, node namespace, topic type, '
'topic type hash, GUID, and QoS Profile of the clients and servers to '
'this service')
arg.completer = ServiceNameCompleter(
include_hidden_services_key='include_hidden_services')

Expand All @@ -44,11 +51,29 @@ def main(self, *, args):
else:
return "Unknown service '%s'" % service_name

line_end = '\n'
if args.verbose:
line_end = '\n\n'

type_str = service_types[0] if len(service_types) == 1 else service_types
print('Type: %s' % type_str, end='\n')

print('Clients count: %d' %
node.count_clients(service_name), end='\n')
node.count_clients(service_name), end=line_end)
if args.verbose:
try:
for info in node.get_clients_info_by_service(service_name):
print(info, end=line_end)

except NotImplementedError as e:
return str(e)

print('Services count: %d' %
node.count_services(service_name), end='\n')
node.count_services(service_name), end=line_end)
if args.verbose:
try:
for info in node.get_servers_info_by_service(service_name):
print(info, end=line_end)

except NotImplementedError as e:
return str(e)