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

Update spawner to have a timeout on service call #1566

Closed
wants to merge 2 commits into from
Closed
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
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,9 @@ class ServiceNotFoundError(Exception):
pass


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

while not cli.service_is_ready():
Expand All @@ -45,14 +47,16 @@ def service_caller(node, service_name, service_type, request, service_timeout=0.

node.get_logger().debug(f"requester: making request: {request}\n")
future = cli.call_async(request)
rclpy.spin_until_future_complete(node, future)
rclpy.spin_until_future_complete(node, future, timeout_sec=call_timeout)
if future.result() is not None:
return future.result()
else:
raise RuntimeError(f"Exception while calling service: {future.exception()}")


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


def list_controllers(node, controller_manager_name, service_timeout=0.0):
def list_controllers(node, controller_manager_name, service_timeout=0.0, call_timeout=10.0):
request = ListControllers.Request()
return service_caller(
node,
f"{controller_manager_name}/list_controllers",
ListControllers,
request,
service_timeout,
call_timeout,
)


def list_controller_types(node, controller_manager_name, service_timeout=0.0):
def list_controller_types(node, controller_manager_name, service_timeout=0.0, call_timeout=10.0):
request = ListControllerTypes.Request()
return service_caller(
node,
f"{controller_manager_name}/list_controller_types",
ListControllerTypes,
request,
service_timeout,
call_timeout,
)


def list_hardware_components(node, controller_manager_name, service_timeout=0.0):
def list_hardware_components(
node, controller_manager_name, service_timeout=0.0, call_timeout=10.0
):
request = ListHardwareComponents.Request()
return service_caller(
node,
f"{controller_manager_name}/list_hardware_components",
ListHardwareComponents,
request,
service_timeout,
call_timeout,
)


def list_hardware_interfaces(node, controller_manager_name, service_timeout=0.0):
def list_hardware_interfaces(
node, controller_manager_name, service_timeout=0.0, call_timeout=10.0
):
request = ListHardwareInterfaces.Request()
return service_caller(
node,
f"{controller_manager_name}/list_hardware_interfaces",
ListHardwareInterfaces,
request,
service_timeout,
call_timeout,
)


def load_controller(node, controller_manager_name, controller_name, service_timeout=0.0):
def load_controller(
node, controller_manager_name, controller_name, service_timeout=0.0, call_timeout=10.0
):
request = LoadController.Request()
request.name = controller_name
return service_caller(
Expand All @@ -117,10 +131,13 @@ def load_controller(node, controller_manager_name, controller_name, service_time
LoadController,
request,
service_timeout,
call_timeout,
)


def reload_controller_libraries(node, controller_manager_name, force_kill, service_timeout=0.0):
def reload_controller_libraries(
node, controller_manager_name, force_kill, service_timeout=0.0, call_timeout=10.0
):
request = ReloadControllerLibraries.Request()
request.force_kill = force_kill
return service_caller(
Expand All @@ -129,11 +146,17 @@ def reload_controller_libraries(node, controller_manager_name, force_kill, servi
ReloadControllerLibraries,
request,
service_timeout,
call_timeout,
)


def set_hardware_component_state(
node, controller_manager_name, component_name, lifecyle_state, service_timeout=0.0
node,
controller_manager_name,
component_name,
lifecyle_state,
service_timeout=0.0,
call_timeout=10.0,
):
request = SetHardwareComponentState.Request()
request.name = component_name
Expand All @@ -144,6 +167,7 @@ def set_hardware_component_state(
SetHardwareComponentState,
request,
service_timeout,
call_timeout,
)


Expand All @@ -170,7 +194,9 @@ def switch_controllers(
)


def unload_controller(node, controller_manager_name, controller_name, service_timeout=0.0):
def unload_controller(
node, controller_manager_name, controller_name, service_timeout=0.0, call_timeout=10.0
):
request = UnloadController.Request()
request.name = controller_name
return service_caller(
Expand All @@ -179,4 +205,5 @@ def unload_controller(node, controller_manager_name, controller_name, service_ti
UnloadController,
request,
service_timeout,
call_timeout,
)
Loading