Skip to content
Merged
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: 0 additions & 2 deletions rclpy/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,6 @@ install(TARGETS rclpy_common

# Split from main extension and converted to pybind11
pybind11_add_module(_rclpy_pybind11 SHARED
src/rclpy/_rclpy_action.cpp
src/rclpy/_rclpy_handle.cpp
src/rclpy/_rclpy_logging.cpp
src/rclpy/_rclpy_pybind11.cpp
Expand All @@ -164,7 +163,6 @@ pybind11_add_module(_rclpy_pybind11 SHARED
src/rclpy/graph.cpp
src/rclpy/guard_condition.cpp
src/rclpy/handle.cpp
src/rclpy/init.cpp
src/rclpy/logging.cpp
src/rclpy/names.cpp
src/rclpy/node.cpp
Expand Down
4 changes: 2 additions & 2 deletions rclpy/rclpy/action/client.py
Original file line number Diff line number Diff line change
Expand Up @@ -149,9 +149,9 @@ def __init__(
self._node = node
self._action_type = action_type
self._action_name = action_name
with node.handle as node_capsule:
with node.handle:
self._client_handle = _rclpy.ActionClient(
node_capsule,
node.handle,
action_type,
action_name,
goal_service_qos_profile.get_c_qos_profile(),
Expand Down
17 changes: 8 additions & 9 deletions rclpy/rclpy/action/graph.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@
from typing import List
from typing import Tuple

from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
from rclpy.node import Node


Expand All @@ -34,9 +33,9 @@ def get_action_client_names_and_types_by_node(
The first element of each tuple is the action name and the second element is a list of
action types.
"""
with node.handle as node_capsule:
return _rclpy.rclpy_action_get_client_names_and_types_by_node(
node_capsule, remote_node_name, remote_node_namespace)
with node.handle:
return node.handle.get_action_client_names_and_types_by_node(
remote_node_name, remote_node_namespace)


def get_action_server_names_and_types_by_node(
Expand All @@ -54,9 +53,9 @@ def get_action_server_names_and_types_by_node(
The first element of each tuple is the action name and the second element is a list of
action types.
"""
with node.handle as node_capsule:
return _rclpy.rclpy_action_get_server_names_and_types_by_node(
node_capsule, remote_node_name, remote_node_namespace)
with node.handle:
return node.handle.get_action_server_names_and_types_by_node(
remote_node_name, remote_node_namespace)


def get_action_names_and_types(node: Node) -> List[Tuple[str, List[str]]]:
Expand All @@ -68,5 +67,5 @@ def get_action_names_and_types(node: Node) -> List[Tuple[str, List[str]]]:
The first element of each tuple is the action name and the second element is a list of
action types.
"""
with node.handle as node_capsule:
return _rclpy.rclpy_action_get_names_and_types(node_capsule)
with node.handle:
return node.handle.get_action_names_and_types()
4 changes: 2 additions & 2 deletions rclpy/rclpy/action/server.py
Original file line number Diff line number Diff line change
Expand Up @@ -240,9 +240,9 @@ def __init__(
check_for_type_support(action_type)
self._node = node
self._action_type = action_type
with node.handle as node_capsule, node.get_clock().handle:
with node.handle, node.get_clock().handle:
self._handle = _rclpy.ActionServer(
node_capsule,
node.handle,
node.get_clock().handle,
action_type,
action_name,
Expand Down
60 changes: 31 additions & 29 deletions rclpy/rclpy/context.py
Original file line number Diff line number Diff line change
Expand Up @@ -34,17 +34,17 @@ class Context:
"""

def __init__(self):
from rclpy.impl.implementation_singleton import rclpy_implementation
from .handle import Handle
self._handle = Handle(rclpy_implementation.rclpy_create_context())
self._lock = threading.Lock()
self._callbacks = []
self._callbacks_lock = threading.Lock()
self._logging_initialized = False

@property
def handle(self):
return self._handle
return self.__context

def destroy(self):
self.__context.destroy_when_not_in_use()

def init(self,
args: Optional[List[str]] = None,
Expand All @@ -57,31 +57,36 @@ def init(self,
:param args: List of command line arguments.
"""
# imported locally to avoid loading extensions on module import
from rclpy.impl.implementation_singleton import rclpy_implementation
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy

global g_logging_ref_count
with self._handle as capsule, self._lock:
with self._lock:
if domain_id is not None and domain_id < 0:
raise RuntimeError(
'Domain id ({}) should not be lower than zero.'
.format(domain_id))
rclpy_implementation.rclpy_init(
args if args is not None else sys.argv,
capsule,
domain_id if domain_id is not None else rclpy_implementation.RCL_DEFAULT_DOMAIN_ID)
if initialize_logging and not self._logging_initialized:
with g_logging_configure_lock:
g_logging_ref_count += 1
if g_logging_ref_count == 1:
rclpy_implementation.rclpy_logging_configure(capsule)
self._logging_initialized = True
try:
if self.__context is not None:
raise RuntimeError
except AttributeError:
self.__context = _rclpy.Context(
args if args is not None else sys.argv,
domain_id if domain_id is not None else _rclpy.RCL_DEFAULT_DOMAIN_ID)
if initialize_logging and not self._logging_initialized:
with g_logging_configure_lock:
g_logging_ref_count += 1
if g_logging_ref_count == 1:
_rclpy.rclpy_logging_configure(self.__context)
self._logging_initialized = True

def ok(self):
"""Check if context hasn't been shut down."""
# imported locally to avoid loading extensions on module import
from rclpy.impl.implementation_singleton import rclpy_implementation
with self._handle as capsule, self._lock:
return rclpy_implementation.rclpy_ok(capsule)
try:
with self.__context, self._lock:
return self.__context.ok()
except AttributeError:
return False

def _call_on_shutdown_callbacks(self):
with self._callbacks_lock:
Expand All @@ -94,19 +99,17 @@ def _call_on_shutdown_callbacks(self):
def shutdown(self):
"""Shutdown this context."""
# imported locally to avoid loading extensions on module import
from rclpy.impl.implementation_singleton import rclpy_implementation
with self._handle as capsule, self._lock:
rclpy_implementation.rclpy_shutdown(capsule)
with self.__context, self._lock:
self.__context.shutdown()
self._call_on_shutdown_callbacks()
self._logging_fini()

def try_shutdown(self):
"""Shutdown this context, if not already shutdown."""
# imported locally to avoid loading extensions on module import
from rclpy.impl.implementation_singleton import rclpy_implementation
with self._handle as capsule, self._lock:
if rclpy_implementation.rclpy_ok(capsule):
rclpy_implementation.rclpy_shutdown(capsule)
with self.__context, self._lock:
if self.__context.ok():
self.__context.shutdown()
self._call_on_shutdown_callbacks()

def _remove_callback(self, weak_method):
Expand Down Expand Up @@ -138,6 +141,5 @@ def _logging_fini(self):

def get_domain_id(self):
"""Get domain id of context."""
from rclpy.impl.implementation_singleton import rclpy_implementation
with self._handle as capsule, self._lock:
return rclpy_implementation.rclpy_context_get_domain_id(capsule)
with self.__context, self._lock:
return self.__context.get_domain_id()
5 changes: 3 additions & 2 deletions rclpy/rclpy/executors.py
Original file line number Diff line number Diff line change
Expand Up @@ -556,15 +556,16 @@ def _wait_for_ready_callbacks(
except InvalidHandle:
pass

context_capsule = context_stack.enter_context(self._context.handle)
context_stack.enter_context(self._context.handle)

wait_set = _rclpy.WaitSet(
entity_count.num_subscriptions,
entity_count.num_guard_conditions,
entity_count.num_timers,
entity_count.num_clients,
entity_count.num_services,
entity_count.num_events,
context_capsule)
self._context.handle)

wait_set.clear_entities()
for sub_handle in sub_handles:
Expand Down
4 changes: 2 additions & 2 deletions rclpy/rclpy/guard_condition.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,8 @@ class GuardCondition:

def __init__(self, callback, callback_group, context=None):
self._context = get_default_context() if context is None else context
with self._context.handle as capsule:
self.__gc = _rclpy.GuardCondition(capsule)
with self._context.handle:
self.__gc = _rclpy.GuardCondition(self._context.handle)
self.callback = callback
self.callback_group = callback_group
# True when the callback is ready to fire but has not been "taken" by an executor
Expand Down
Loading