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

Lazily import C extensions #422

Closed
Closed
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
24 changes: 9 additions & 15 deletions rclpy/rclpy/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -42,9 +42,12 @@

import sys
from typing import List
from typing import TYPE_CHECKING

from rclpy.context import Context
from rclpy.executors import Executor
from rclpy.executors import SingleThreadedExecutor
from rclpy.impl.implementation_singleton import get_rclpy_implementation
from rclpy.node import Node
from rclpy.parameter import Parameter
from rclpy.task import Future
from rclpy.utilities import get_default_context
Expand All @@ -53,11 +56,6 @@
from rclpy.utilities import shutdown as _shutdown
from rclpy.utilities import try_shutdown # noqa: F401

# Avoid loading extensions on module import
if TYPE_CHECKING:
from rclpy.executors import Executor # noqa: F401
from rclpy.node import Node # noqa: F401


def init(*, args: List[str] = None, context: Context = None) -> None:
"""
Expand All @@ -68,21 +66,19 @@ def init(*, args: List[str] = None, context: Context = None) -> None:
(see :func:`.get_default_context`).
"""
context = get_default_context() if context is None else context
# imported locally to avoid loading extensions on module import
from rclpy.impl.implementation_singleton import rclpy_implementation
return rclpy_implementation.rclpy_init(args if args is not None else sys.argv, context.handle)
return get_rclpy_implementation().rclpy_init(
args if args is not None else sys.argv, context.handle
)


# The global spin functions need an executor to do the work
# A persistent executor can re-run async tasks that yielded in rclpy.spin*().
__executor = None


def get_global_executor() -> 'Executor':
def get_global_executor() -> Executor:
global __executor
if __executor is None:
# imported locally to avoid loading extensions on module import
from rclpy.executors import SingleThreadedExecutor
__executor = SingleThreadedExecutor()
return __executor

Expand Down Expand Up @@ -114,7 +110,7 @@ def create_node(
parameter_overrides: List[Parameter] = None,
allow_undeclared_parameters: bool = False,
automatically_declare_parameters_from_overrides: bool = False
) -> 'Node':
) -> Node:
"""
Create an instance of :class:`.Node`.

Expand All @@ -136,8 +132,6 @@ def create_node(
be used to implicitly declare parameters on the node during creation, default False.
:return: An instance of the newly created node.
"""
# imported locally to avoid loading extensions on module import
from rclpy.node import Node # noqa: F811
return Node(
node_name, context=context, cli_args=cli_args, namespace=namespace,
use_global_arguments=use_global_arguments,
Expand Down
62 changes: 40 additions & 22 deletions rclpy/rclpy/action/client.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,9 +21,8 @@
from action_msgs.srv import CancelGoal

from rclpy.executors import await_or_execute
from rclpy.impl.implementation_singleton import rclpy_action_implementation as _rclpy_action
from rclpy.qos import qos_profile_action_status_default
from rclpy.qos import qos_profile_services_default
from rclpy.impl.implementation_singleton import get_rclpy_action_implementation
from rclpy.qos import qos_profiles
from rclpy.qos import QoSProfile
from rclpy.task import Future
from rclpy.type_support import check_for_type_support
Expand Down Expand Up @@ -118,11 +117,11 @@ def __init__(
action_name,
*,
callback_group=None,
goal_service_qos_profile=qos_profile_services_default,
result_service_qos_profile=qos_profile_services_default,
cancel_service_qos_profile=qos_profile_services_default,
feedback_sub_qos_profile=QoSProfile(depth=10),
status_sub_qos_profile=qos_profile_action_status_default
goal_service_qos_profile=None,
result_service_qos_profile=None,
cancel_service_qos_profile=None,
feedback_sub_qos_profile=None,
status_sub_qos_profile=None
):
"""
Constructor.
Expand All @@ -139,6 +138,17 @@ def __init__(
:param feedback_sub_qos_profile: QoS profile for the feedback subscriber.
:param status_sub_qos_profile: QoS profile for the status subscriber.
"""
if goal_service_qos_profile is None:
goal_service_qos_profile = qos_profiles.services_default
if result_service_qos_profile is None:
result_service_qos_profile = qos_profiles.services_default
if cancel_service_qos_profile is None:
cancel_service_qos_profile = qos_profiles.services_default
if feedback_sub_qos_profile is None:
feedback_sub_qos_profile = QoSProfile(depth=10)
if status_sub_qos_profile is None:
status_sub_qos_profile = qos_profiles.action_status_default

if callback_group is None:
callback_group = node.default_callback_group

Expand All @@ -149,7 +159,7 @@ def __init__(
self._node = node
self._action_type = action_type
with node.handle as node_capsule:
self._client_handle = _rclpy_action.rclpy_action_create_client(
self._client_handle = get_rclpy_action_implementation().rclpy_action_create_client(
node_capsule,
action_type,
action_name,
Expand Down Expand Up @@ -219,7 +229,7 @@ def _remove_pending_result_request(self, future):
# Start Waitable API
def is_ready(self, wait_set):
"""Return True if one or more entities are ready in the wait set."""
ready_entities = _rclpy_action.rclpy_action_wait_set_is_ready(
ready_entities = get_rclpy_action_implementation().rclpy_action_wait_set_is_ready(
self._client_handle,
wait_set)
self._is_feedback_ready = ready_entities[0]
Expand All @@ -233,35 +243,35 @@ def take_data(self):
"""Take stuff from lower level so the wait set doesn't immediately wake again."""
data = {}
if self._is_goal_response_ready:
taken_data = _rclpy_action.rclpy_action_take_goal_response(
taken_data = get_rclpy_action_implementation().rclpy_action_take_goal_response(
self._client_handle, self._action_type.Impl.SendGoalService.Response)
# If take fails, then we get (None, None)
if all(taken_data):
data['goal'] = taken_data

if self._is_cancel_response_ready:
taken_data = _rclpy_action.rclpy_action_take_cancel_response(
taken_data = get_rclpy_action_implementation().rclpy_action_take_cancel_response(
self._client_handle, self._action_type.Impl.CancelGoalService.Response)
# If take fails, then we get (None, None)
if all(taken_data):
data['cancel'] = taken_data

if self._is_result_response_ready:
taken_data = _rclpy_action.rclpy_action_take_result_response(
taken_data = get_rclpy_action_implementation().rclpy_action_take_result_response(
self._client_handle, self._action_type.Impl.GetResultService.Response)
# If take fails, then we get (None, None)
if all(taken_data):
data['result'] = taken_data

if self._is_feedback_ready:
taken_data = _rclpy_action.rclpy_action_take_feedback(
taken_data = get_rclpy_action_implementation().rclpy_action_take_feedback(
self._client_handle, self._action_type.Impl.FeedbackMessage)
# If take fails, then we get None
if taken_data is not None:
data['feedback'] = taken_data

if self._is_status_ready:
taken_data = _rclpy_action.rclpy_action_take_status(
taken_data = get_rclpy_action_implementation().rclpy_action_take_status(
self._client_handle, self._action_type.Impl.GoalStatusMessage)
# If take fails, then we get None
if taken_data is not None:
Expand Down Expand Up @@ -328,12 +338,17 @@ async def execute(self, taken_data):

def get_num_entities(self):
"""Return number of each type of entity used in the wait set."""
num_entities = _rclpy_action.rclpy_action_wait_set_get_num_entities(self._client_handle)
num_entities = get_rclpy_action_implementation().rclpy_action_wait_set_get_num_entities(
self._client_handle
)
return NumberOfEntities(*num_entities)

def add_to_wait_set(self, wait_set):
"""Add entities to wait set."""
_rclpy_action.rclpy_action_wait_set_add(self._client_handle, wait_set)
get_rclpy_action_implementation().rclpy_action_wait_set_add(
self._client_handle,
wait_set
)
# End Waitable API

def send_goal(self, goal, **kwargs):
Expand Down Expand Up @@ -404,7 +419,7 @@ def send_goal_async(self, goal, feedback_callback=None, goal_uuid=None):
request = self._action_type.Impl.SendGoalService.Request()
request.goal_id = self._generate_random_uuid() if goal_uuid is None else goal_uuid
request.goal = goal
sequence_number = _rclpy_action.rclpy_action_send_goal_request(
sequence_number = get_rclpy_action_implementation().rclpy_action_send_goal_request(
self._client_handle, request)
if sequence_number in self._pending_goal_requests:
raise RuntimeError(
Expand Down Expand Up @@ -463,7 +478,7 @@ def _cancel_goal_async(self, goal_handle):

cancel_request = CancelGoal.Request()
cancel_request.goal_info.goal_id = goal_handle.goal_id
sequence_number = _rclpy_action.rclpy_action_send_cancel_request(
sequence_number = get_rclpy_action_implementation().rclpy_action_send_cancel_request(
self._client_handle,
cancel_request)
if sequence_number in self._pending_cancel_requests:
Expand Down Expand Up @@ -517,7 +532,7 @@ def _get_result_async(self, goal_handle):

result_request = self._action_type.Impl.GetResultService.Request()
result_request.goal_id = goal_handle.goal_id
sequence_number = _rclpy_action.rclpy_action_send_result_request(
sequence_number = get_rclpy_action_implementation().rclpy_action_send_result_request(
self._client_handle,
result_request)
if sequence_number in self._pending_result_requests:
Expand All @@ -539,7 +554,7 @@ def server_is_ready(self):
:return: True if an action server is ready, False otherwise.
"""
with self._node.handle as node_capsule:
return _rclpy_action.rclpy_action_server_is_available(
return get_rclpy_action_implementation().rclpy_action_server_is_available(
node_capsule,
self._client_handle)

Expand Down Expand Up @@ -568,7 +583,10 @@ def destroy(self):
if self._client_handle is None:
return
with self._node.handle as node_capsule:
_rclpy_action.rclpy_action_destroy_entity(self._client_handle, node_capsule)
get_rclpy_action_implementation().rclpy_action_destroy_entity(
self._client_handle,
node_capsule
)
self._node.remove_waitable(self)
self._client_handle = None

Expand Down
8 changes: 4 additions & 4 deletions rclpy/rclpy/action/graph.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
from typing import List
from typing import Tuple

from rclpy.impl.implementation_singleton import rclpy_action_implementation as _rclpy_action
from rclpy.impl.implementation_singleton import get_rclpy_action_implementation
from rclpy.node import Node


Expand All @@ -35,7 +35,7 @@ def get_action_client_names_and_types_by_node(
action types.
"""
with node.handle as node_capsule:
return _rclpy_action.rclpy_action_get_client_names_and_types_by_node(
return get_rclpy_action_implementation().rclpy_action_get_client_names_and_types_by_node(
node_capsule, remote_node_name, remote_node_namespace)


Expand All @@ -55,7 +55,7 @@ def get_action_server_names_and_types_by_node(
action types.
"""
with node.handle as node_capsule:
return _rclpy_action.rclpy_action_get_server_names_and_types_by_node(
return get_rclpy_action_implementation().rclpy_action_get_server_names_and_types_by_node(
node_capsule, remote_node_name, remote_node_namespace)


Expand All @@ -69,4 +69,4 @@ def get_action_names_and_types(node: Node) -> List[Tuple[str, List[str]]]:
action types.
"""
with node.handle as node_capsule:
return _rclpy_action.rclpy_action_get_names_and_types(node_capsule)
return get_rclpy_action_implementation().rclpy_action_get_names_and_types(node_capsule)
Loading