Skip to content

Commit

Permalink
Handle on waiting (backport #1562) (#1681)
Browse files Browse the repository at this point in the history
* Handle waiting in Spawner and align Hardware Spawner functionality (#1562)

(cherry picked from commit af4b48f)

---------

Co-authored-by: Bence Magyar <bence.magyar.robotics@gmail.com>
Co-authored-by: Dr. Denis <denis@stoglrobotics.de>
  • Loading branch information
3 people committed Aug 15, 2024
1 parent 930475c commit 41723d2
Show file tree
Hide file tree
Showing 9 changed files with 542 additions and 160 deletions.
4 changes: 4 additions & 0 deletions controller_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -182,13 +182,17 @@ if(BUILD_TESTING)

ament_add_gmock(test_spawner_unspawner
test/test_spawner_unspawner.cpp
TIMEOUT 120
)
target_link_libraries(test_spawner_unspawner
controller_manager
test_controller
ros2_control_test_assets::ros2_control_test_assets
)

install(FILES test/test_controller_spawner_with_type.yaml
DESTINATION test)

ament_add_gmock(test_hardware_management_srvs
test/test_hardware_management_srvs.cpp
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,15 +28,20 @@
import rclpy


def service_caller(node, service_name, service_type, request, service_timeout=10.0):
class ServiceNotFoundError(Exception):
pass


def service_caller(node, service_name, service_type, request, service_timeout=0.0):
cli = node.create_client(service_type, service_name)

if not cli.service_is_ready():
node.get_logger().debug(
f"waiting {service_timeout} seconds for service {service_name} to become available..."
)
if not cli.wait_for_service(service_timeout):
raise RuntimeError(f"Could not contact service {service_name}")
while not cli.service_is_ready():
node.get_logger().info(f"waiting for service {service_name} to become available...")
if service_timeout:
if not cli.wait_for_service(service_timeout):
raise ServiceNotFoundError(f"Could not contact service {service_name}")
elif not cli.wait_for_service(10.0):
node.get_logger().warn(f"Could not contact service {service_name}")

node.get_logger().debug(f"requester: making request: {request}\n")
future = cli.call_async(request)
Expand All @@ -47,7 +52,7 @@ def service_caller(node, service_name, service_type, request, service_timeout=10
raise RuntimeError(f"Exception while calling service: {future.exception()}")


def configure_controller(node, controller_manager_name, controller_name, service_timeout=10.0):
def configure_controller(node, controller_manager_name, controller_name, service_timeout=0.0):
request = ConfigureController.Request()
request.name = controller_name
return service_caller(
Expand All @@ -59,7 +64,7 @@ def configure_controller(node, controller_manager_name, controller_name, service
)


def list_controllers(node, controller_manager_name, service_timeout=10.0):
def list_controllers(node, controller_manager_name, service_timeout=0.0):
request = ListControllers.Request()
return service_caller(
node,
Expand All @@ -70,7 +75,7 @@ def list_controllers(node, controller_manager_name, service_timeout=10.0):
)


def list_controller_types(node, controller_manager_name, service_timeout=10.0):
def list_controller_types(node, controller_manager_name, service_timeout=0.0):
request = ListControllerTypes.Request()
return service_caller(
node,
Expand All @@ -81,7 +86,7 @@ def list_controller_types(node, controller_manager_name, service_timeout=10.0):
)


def list_hardware_components(node, controller_manager_name, service_timeout=10.0):
def list_hardware_components(node, controller_manager_name, service_timeout=0.0):
request = ListHardwareComponents.Request()
return service_caller(
node,
Expand All @@ -92,7 +97,7 @@ def list_hardware_components(node, controller_manager_name, service_timeout=10.0
)


def list_hardware_interfaces(node, controller_manager_name, service_timeout=10.0):
def list_hardware_interfaces(node, controller_manager_name, service_timeout=0.0):
request = ListHardwareInterfaces.Request()
return service_caller(
node,
Expand All @@ -103,7 +108,7 @@ def list_hardware_interfaces(node, controller_manager_name, service_timeout=10.0
)


def load_controller(node, controller_manager_name, controller_name, service_timeout=10.0):
def load_controller(node, controller_manager_name, controller_name, service_timeout=0.0):
request = LoadController.Request()
request.name = controller_name
return service_caller(
Expand All @@ -115,7 +120,7 @@ def load_controller(node, controller_manager_name, controller_name, service_time
)


def reload_controller_libraries(node, controller_manager_name, force_kill, service_timeout=10.0):
def reload_controller_libraries(node, controller_manager_name, force_kill, service_timeout=0.0):
request = ReloadControllerLibraries.Request()
request.force_kill = force_kill
return service_caller(
Expand All @@ -128,7 +133,7 @@ def reload_controller_libraries(node, controller_manager_name, force_kill, servi


def set_hardware_component_state(
node, controller_manager_name, component_name, lifecyle_state, service_timeout=10.0
node, controller_manager_name, component_name, lifecyle_state, service_timeout=0.0
):
request = SetHardwareComponentState.Request()
request.name = component_name
Expand Down Expand Up @@ -165,7 +170,7 @@ def switch_controllers(
)


def unload_controller(node, controller_manager_name, controller_name, service_timeout=10.0):
def unload_controller(node, controller_manager_name, controller_name, service_timeout=0.0):
request = UnloadController.Request()
request.name = controller_name
return service_caller(
Expand Down
77 changes: 25 additions & 52 deletions controller_manager/controller_manager/hardware_spawner.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,13 +15,15 @@

import argparse
import sys
import time

from controller_manager import set_hardware_component_state
from controller_manager import (
list_hardware_components,
set_hardware_component_state,
)
from controller_manager.controller_manager_services import ServiceNotFoundError

from lifecycle_msgs.msg import State
import rclpy
from rclpy.duration import Duration
from rclpy.node import Node
from rclpy.signals import SignalHandlerOptions

Expand All @@ -43,17 +45,6 @@ def first_match(iterable, predicate):
return next((n for n in iterable if predicate(n)), None)


def wait_for_value_or(function, node, timeout, default, description):
while node.get_clock().now() < timeout:
if result := function():
return result
node.get_logger().info(
f"Waiting for {description}", throttle_duration_sec=2, skip_first=True
)
time.sleep(0.2)
return default


def combine_name_and_namespace(name_and_namespace):
node_name, namespace = name_and_namespace
return namespace + ("" if namespace.endswith("/") else "/") + node_name
Expand All @@ -75,35 +66,11 @@ def has_service_names(node, node_name, node_namespace, service_names):
return all(service in client_names for service in service_names)


def wait_for_controller_manager(node, controller_manager, timeout_duration):
# List of service names from controller_manager we wait for
service_names = (
f"{controller_manager}/list_hardware_components",
f"{controller_manager}/set_hardware_component_state",
)

# Wait for controller_manager
timeout = node.get_clock().now() + Duration(seconds=timeout_duration)
node_and_namespace = wait_for_value_or(
lambda: find_node_and_namespace(node, controller_manager),
node,
timeout,
None,
f"'{controller_manager}' node to exist",
)

# Wait for the services if the node was found
if node_and_namespace:
node_name, namespace = node_and_namespace
return wait_for_value_or(
lambda: has_service_names(node, node_name, namespace, service_names),
node,
timeout,
False,
f"'{controller_manager}' services to be available",
)

return False
def is_hardware_component_loaded(
node, controller_manager, hardware_component, service_timeout=0.0
):
components = list_hardware_components(node, hardware_component, service_timeout).component
return any(c.name == hardware_component for c in components)


def handle_set_component_state_service_call(
Expand Down Expand Up @@ -167,10 +134,9 @@ def main(args=None):
"--controller-manager-timeout",
help="Time to wait for the controller manager",
required=False,
default=10,
type=int,
default=0,
type=float,
)

# add arguments which are mutually exclusive
activate_or_confiigure_grp.add_argument(
"--activate",
Expand Down Expand Up @@ -202,13 +168,15 @@ def main(args=None):
controller_manager_name = f"/{controller_manager_name}"

try:
if not wait_for_controller_manager(
node, controller_manager_name, controller_manager_timeout
if not is_hardware_component_loaded(
node, controller_manager_name, hardware_component, controller_manager_timeout
):
node.get_logger().error("Controller manager not available")
return 1

if activate:
node.get_logger().warn(
bcolors.WARNING
+ "Hardware Component is not loaded - state can not be changed."
+ bcolors.ENDC
)
elif activate:
activate_components(node, controller_manager_name, hardware_component)
elif configure:
configure_components(node, controller_manager_name, hardware_component)
Expand All @@ -218,6 +186,11 @@ def main(args=None):
)
parser.print_help()
return 0
except KeyboardInterrupt:
pass
except ServiceNotFoundError as err:
node.get_logger().fatal(str(err))
return 1
finally:
rclpy.shutdown()

Expand Down
Loading

0 comments on commit 41723d2

Please sign in to comment.