mirror of https://github.com/ros2/rclpy
refactor to allow for non-global init (#249)
* refactor to allow for non-global init Signed-off-by: William Woodall <william@osrfoundation.org> * fixes found during testing Signed-off-by: William Woodall <william@osrfoundation.org> * gitignore pytest cache Signed-off-by: William Woodall <william@osrfoundation.org> * fixes found while testing Signed-off-by: William Woodall <william@osrfoundation.org>
This commit is contained in:
parent
c4ef386c16
commit
5b95169e6f
|
@ -55,3 +55,4 @@ docs/_build/
|
|||
|
||||
# PyBuilder
|
||||
target/
|
||||
.pytest_cache
|
||||
|
|
|
@ -14,17 +14,18 @@
|
|||
|
||||
import sys
|
||||
|
||||
from rclpy.utilities import get_default_context
|
||||
from rclpy.utilities import get_rmw_implementation_identifier # noqa
|
||||
from rclpy.utilities import ok
|
||||
from rclpy.utilities import ok # noqa: forwarding to this module
|
||||
from rclpy.utilities import shutdown as _shutdown
|
||||
from rclpy.utilities import try_shutdown # noqa
|
||||
|
||||
|
||||
def init(*, args=None):
|
||||
def init(*, args=None, context=None):
|
||||
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)
|
||||
return 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
|
||||
|
@ -41,22 +42,23 @@ def get_global_executor():
|
|||
return __executor
|
||||
|
||||
|
||||
def shutdown():
|
||||
def shutdown(*, context=None):
|
||||
global __executor
|
||||
if __executor is not None:
|
||||
__executor.shutdown()
|
||||
__executor = None
|
||||
_shutdown()
|
||||
_shutdown(context=context)
|
||||
|
||||
|
||||
def create_node(
|
||||
node_name, *, cli_args=None, namespace=None, use_global_arguments=True,
|
||||
node_name, *, context=None, cli_args=None, namespace=None, use_global_arguments=True,
|
||||
start_parameter_services=True, initial_parameters=None
|
||||
):
|
||||
"""
|
||||
Create an instance of :class:`rclpy.node.Node`.
|
||||
|
||||
:param node_name: A unique name to give to this node
|
||||
:param node_name: A unique name to give to this node.
|
||||
:param context: The context to be associated with, or None for the default global context.
|
||||
:param cli_args: A list of strings of command line args to be used only by this node.
|
||||
:param namespace: The namespace to which relative topic and service names will be prefixed.
|
||||
:param use_global_arguments: False if the node should ignore process-wide command line args.
|
||||
|
@ -68,13 +70,13 @@ def create_node(
|
|||
# imported locally to avoid loading extensions on module import
|
||||
from rclpy.node import Node
|
||||
return Node(
|
||||
node_name, cli_args=cli_args, namespace=namespace,
|
||||
node_name, context=context, cli_args=cli_args, namespace=namespace,
|
||||
use_global_arguments=use_global_arguments,
|
||||
start_parameter_services=start_parameter_services,
|
||||
initial_parameters=initial_parameters)
|
||||
|
||||
|
||||
def spin_once(node, *, timeout_sec=None):
|
||||
def spin_once(node, *, executor=None, timeout_sec=None):
|
||||
"""
|
||||
Execute one item of work or wait until timeout expires.
|
||||
|
||||
|
@ -85,11 +87,12 @@ def spin_once(node, *, timeout_sec=None):
|
|||
if the global executor has a partially completed coroutine.
|
||||
|
||||
:param node: A node to add to the executor to check for work.
|
||||
:param executor: The executor to use, or the global executor if None is passed.
|
||||
:param timeout_sec: Seconds to wait. Block forever if None or negative. Don't wait if 0
|
||||
:return: Always returns None regardless whether work executes or timeout expires.
|
||||
:rtype: None
|
||||
"""
|
||||
executor = get_global_executor()
|
||||
executor = get_global_executor() if executor is None else executor
|
||||
try:
|
||||
executor.add_node(node)
|
||||
executor.spin_once(timeout_sec=timeout_sec)
|
||||
|
@ -97,7 +100,7 @@ def spin_once(node, *, timeout_sec=None):
|
|||
executor.remove_node(node)
|
||||
|
||||
|
||||
def spin(node):
|
||||
def spin(node, executor=None):
|
||||
"""
|
||||
Execute work blocking until the library is shutdown.
|
||||
|
||||
|
@ -105,29 +108,32 @@ def spin(node):
|
|||
This method blocks.
|
||||
|
||||
:param node: A node to add to the executor to check for work.
|
||||
:param executor: The executor to use, or the global executor if None is passed.
|
||||
:return: Always returns None regardless whether work executes or timeout expires.
|
||||
:rtype: None
|
||||
"""
|
||||
executor = get_global_executor()
|
||||
executor = get_global_executor() if executor is None else executor
|
||||
try:
|
||||
executor.add_node(node)
|
||||
while ok():
|
||||
while executor.context.ok():
|
||||
executor.spin_once()
|
||||
finally:
|
||||
executor.remove_node(node)
|
||||
|
||||
|
||||
def spin_until_future_complete(node, future):
|
||||
def spin_until_future_complete(node, future, executor=None):
|
||||
"""
|
||||
Execute work until the future is complete.
|
||||
|
||||
Callbacks and other work will be executed in a SingleThreadedExecutor until future.done()
|
||||
returns True or rclpy is shutdown.
|
||||
|
||||
:param node: A node to add to the executor to check for work.
|
||||
:param future: The future object to wait on.
|
||||
:param executor: The executor to use, or the global executor if None is passed.
|
||||
:type future: rclpy.task.Future
|
||||
"""
|
||||
executor = get_global_executor()
|
||||
executor = get_global_executor() if executor is None else executor
|
||||
try:
|
||||
executor.add_node(node)
|
||||
executor.spin_until_future_complete(future)
|
||||
|
|
|
@ -17,14 +17,14 @@ import time
|
|||
|
||||
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
|
||||
from rclpy.task import Future
|
||||
import rclpy.utilities
|
||||
|
||||
|
||||
class Client:
|
||||
def __init__(
|
||||
self, node_handle, client_handle, client_pointer,
|
||||
self, node_handle, context, client_handle, client_pointer,
|
||||
srv_type, srv_name, qos_profile, callback_group):
|
||||
self.node_handle = node_handle
|
||||
self.context = context
|
||||
self.client_handle = client_handle
|
||||
self.client_pointer = client_pointer
|
||||
self.srv_type = srv_type
|
||||
|
@ -102,7 +102,7 @@ class Client:
|
|||
sleep_time = 0.25
|
||||
if timeout_sec is None:
|
||||
timeout_sec = float('inf')
|
||||
while rclpy.utilities.ok() and not self.service_is_ready() and timeout_sec > 0.0:
|
||||
while self.context.ok() and not self.service_is_ready() and timeout_sec > 0.0:
|
||||
time.sleep(sleep_time)
|
||||
timeout_sec -= sleep_time
|
||||
|
||||
|
|
|
@ -0,0 +1,54 @@
|
|||
# Copyright 2018 Open Source Robotics Foundation, Inc.
|
||||
#
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
#
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
#
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
|
||||
import threading
|
||||
|
||||
|
||||
class Context:
|
||||
"""
|
||||
Encapsulates the lifecycle of init and shutdown.
|
||||
|
||||
Context objects should not be reused, and are finalized in their destructor.
|
||||
|
||||
Wraps the `rcl_context_t` type.
|
||||
"""
|
||||
|
||||
def __init__(self):
|
||||
from rclpy.impl.implementation_singleton import rclpy_implementation
|
||||
self._handle = rclpy_implementation.rclpy_create_context()
|
||||
self._lock = threading.Lock()
|
||||
|
||||
@property
|
||||
def handle(self):
|
||||
return self._handle
|
||||
|
||||
def ok(self):
|
||||
# imported locally to avoid loading extensions on module import
|
||||
from rclpy.impl.implementation_singleton import rclpy_implementation
|
||||
with self._lock:
|
||||
return rclpy_implementation.rclpy_ok(self._handle)
|
||||
|
||||
def shutdown(self):
|
||||
# imported locally to avoid loading extensions on module import
|
||||
from rclpy.impl.implementation_singleton import rclpy_implementation
|
||||
with self._lock:
|
||||
return rclpy_implementation.rclpy_shutdown(self._handle)
|
||||
|
||||
def try_shutdown(self):
|
||||
"""Shutdown rclpy if not already shutdown."""
|
||||
# imported locally to avoid loading extensions on module import
|
||||
from rclpy.impl.implementation_singleton import rclpy_implementation
|
||||
with self._lock:
|
||||
if rclpy_implementation.rclpy_ok(self._handle):
|
||||
return rclpy_implementation.rclpy_shutdown(self._handle)
|
|
@ -22,7 +22,7 @@ from threading import RLock
|
|||
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
|
||||
from rclpy.task import Task
|
||||
from rclpy.timer import WallTimer
|
||||
from rclpy.utilities import ok
|
||||
from rclpy.utilities import get_default_context
|
||||
from rclpy.utilities import timeout_sec_to_nsec
|
||||
from rclpy.waitable import NumberOfEntities
|
||||
|
||||
|
@ -108,17 +108,20 @@ class Executor:
|
|||
|
||||
A custom executor must define :func:`Executor.spin_once`. If the executor has any cleanup then
|
||||
it should also define :func:`Executor.shutdown`.
|
||||
|
||||
:param context: The context to be associated with, or None for the default global context.
|
||||
"""
|
||||
|
||||
def __init__(self):
|
||||
def __init__(self, *, context=None):
|
||||
super().__init__()
|
||||
self._context = get_default_context() if context is None else context
|
||||
self._nodes = set()
|
||||
self._nodes_lock = RLock()
|
||||
# Tasks to be executed (oldest first) 3-tuple Task, Entity, Node
|
||||
self._tasks = []
|
||||
self._tasks_lock = Lock()
|
||||
# This is triggered when wait_for_ready_callbacks should rebuild the wait list
|
||||
gc, gc_handle = _rclpy.rclpy_create_guard_condition()
|
||||
gc, gc_handle = _rclpy.rclpy_create_guard_condition(self._context.handle)
|
||||
self._guard_condition = gc
|
||||
self._guard_condition_handle = gc_handle
|
||||
# True if shutdown has been called
|
||||
|
@ -129,6 +132,10 @@ class Executor:
|
|||
self._last_args = None
|
||||
self._last_kwargs = None
|
||||
|
||||
@property
|
||||
def context(self):
|
||||
return self._context
|
||||
|
||||
def create_task(self, callback, *args, **kwargs):
|
||||
"""
|
||||
Add a callback or coroutine to be executed during :meth:`spin` and return a Future.
|
||||
|
@ -212,12 +219,12 @@ class Executor:
|
|||
|
||||
def spin(self):
|
||||
"""Execute callbacks until shutdown."""
|
||||
while ok():
|
||||
while self._context.ok():
|
||||
self.spin_once()
|
||||
|
||||
def spin_until_future_complete(self, future):
|
||||
"""Execute until a given future is done."""
|
||||
while ok() and not future.done():
|
||||
while self._context.ok() and not future.done():
|
||||
self.spin_once()
|
||||
|
||||
def spin_once(self, timeout_sec=None):
|
||||
|
@ -419,7 +426,8 @@ class Executor:
|
|||
)
|
||||
for waitable in waitables:
|
||||
waitable.add_to_wait_set(wait_set)
|
||||
(sigint_gc, sigint_gc_handle) = _rclpy.rclpy_get_sigint_guard_condition()
|
||||
(sigint_gc, sigint_gc_handle) = \
|
||||
_rclpy.rclpy_get_sigint_guard_condition(self._context.handle)
|
||||
try:
|
||||
_rclpy.rclpy_wait_set_add_entity('guard_condition', wait_set, sigint_gc)
|
||||
_rclpy.rclpy_wait_set_add_entity(
|
||||
|
@ -541,6 +549,9 @@ class Executor:
|
|||
class SingleThreadedExecutor(Executor):
|
||||
"""Runs callbacks in the thread which calls :func:`SingleThreadedExecutor.spin`."""
|
||||
|
||||
def __init__(self, *, context=None):
|
||||
super().__init__(context=context)
|
||||
|
||||
def spin_once(self, timeout_sec=None):
|
||||
try:
|
||||
handler, entity, node = self.wait_for_ready_callbacks(timeout_sec=timeout_sec)
|
||||
|
@ -555,7 +566,7 @@ class SingleThreadedExecutor(Executor):
|
|||
class MultiThreadedExecutor(Executor):
|
||||
"""Runs callbacks in a pool of threads."""
|
||||
|
||||
def __init__(self, num_threads=None):
|
||||
def __init__(self, num_threads=None, *, context=None):
|
||||
"""
|
||||
Initialize the executor.
|
||||
|
||||
|
@ -564,7 +575,7 @@ class MultiThreadedExecutor(Executor):
|
|||
of threads defaults to 1.
|
||||
:type num_threads: int
|
||||
"""
|
||||
super().__init__()
|
||||
super().__init__(context=context)
|
||||
if num_threads is None:
|
||||
try:
|
||||
num_threads = multiprocessing.cpu_count()
|
||||
|
|
|
@ -13,12 +13,15 @@
|
|||
# limitations under the License.
|
||||
|
||||
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
|
||||
from rclpy.utilities import get_default_context
|
||||
|
||||
|
||||
class GuardCondition:
|
||||
|
||||
def __init__(self, callback, callback_group):
|
||||
self.guard_handle, self.guard_pointer = _rclpy.rclpy_create_guard_condition()
|
||||
def __init__(self, callback, callback_group, context=None):
|
||||
self._context = get_default_context() if context is None else context
|
||||
self.guard_handle, self.guard_pointer = \
|
||||
_rclpy.rclpy_create_guard_condition(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
|
||||
|
|
|
@ -34,7 +34,7 @@ from rclpy.service import Service
|
|||
from rclpy.subscription import Subscription
|
||||
from rclpy.time_source import TimeSource
|
||||
from rclpy.timer import WallTimer
|
||||
from rclpy.utilities import ok
|
||||
from rclpy.utilities import get_default_context
|
||||
from rclpy.validate_full_topic_name import validate_full_topic_name
|
||||
from rclpy.validate_namespace import validate_namespace
|
||||
from rclpy.validate_node_name import validate_node_name
|
||||
|
@ -60,10 +60,11 @@ def check_for_type_support(msg_type):
|
|||
class Node:
|
||||
|
||||
def __init__(
|
||||
self, node_name, *, cli_args=None, namespace=None, use_global_arguments=True,
|
||||
self, node_name, *, context=None, cli_args=None, namespace=None, use_global_arguments=True,
|
||||
start_parameter_services=True, initial_parameters=None
|
||||
):
|
||||
self._handle = None
|
||||
self._context = get_default_context() if context is None else context
|
||||
self._parameters = {}
|
||||
self.publishers = []
|
||||
self.subscriptions = []
|
||||
|
@ -76,11 +77,11 @@ class Node:
|
|||
self._parameters_callback = None
|
||||
|
||||
namespace = namespace or ''
|
||||
if not ok():
|
||||
if not self._context.ok():
|
||||
raise NotInitializedException('cannot create node')
|
||||
try:
|
||||
self._handle = _rclpy.rclpy_create_node(
|
||||
node_name, namespace, cli_args, use_global_arguments)
|
||||
node_name, namespace, self._context.handle, cli_args, use_global_arguments)
|
||||
except ValueError:
|
||||
# these will raise more specific errors if the name or namespace is bad
|
||||
validate_node_name(node_name)
|
||||
|
@ -132,6 +133,10 @@ class Node:
|
|||
elif new_executor.add_node(self):
|
||||
self.__executor_weakref = weakref.ref(new_executor)
|
||||
|
||||
@property
|
||||
def context(self):
|
||||
return self._context
|
||||
|
||||
@property
|
||||
def handle(self):
|
||||
return self._handle
|
||||
|
@ -278,7 +283,8 @@ class Node:
|
|||
if failed:
|
||||
self._validate_topic_or_service_name(srv_name, is_service=True)
|
||||
client = Client(
|
||||
self.handle, client_handle, client_pointer, srv_type, srv_name, qos_profile,
|
||||
self.handle, self.context,
|
||||
client_handle, client_pointer, srv_type, srv_name, qos_profile,
|
||||
callback_group)
|
||||
self.clients.append(client)
|
||||
callback_group.add_entity(client)
|
||||
|
@ -312,7 +318,7 @@ class Node:
|
|||
timer_period_nsec = int(float(timer_period_sec) * S_TO_NS)
|
||||
if callback_group is None:
|
||||
callback_group = self._default_callback_group
|
||||
timer = WallTimer(callback, callback_group, timer_period_nsec)
|
||||
timer = WallTimer(callback, callback_group, timer_period_nsec, context=self.context)
|
||||
|
||||
self.timers.append(timer)
|
||||
callback_group.add_entity(timer)
|
||||
|
@ -321,7 +327,7 @@ class Node:
|
|||
def create_guard_condition(self, callback, callback_group=None):
|
||||
if callback_group is None:
|
||||
callback_group = self._default_callback_group
|
||||
guard = GuardCondition(callback, callback_group)
|
||||
guard = GuardCondition(callback, callback_group, context=self.context)
|
||||
|
||||
self.guards.append(guard)
|
||||
callback_group.add_entity(guard)
|
||||
|
|
|
@ -47,8 +47,8 @@ class Future:
|
|||
def __del__(self):
|
||||
if self._exception is not None and not self._exception_fetched:
|
||||
print(
|
||||
'The following exception was never retrieved: ' +
|
||||
str(self._exception), file=sys.stderr)
|
||||
'The following exception was never retrieved: ' + str(self._exception),
|
||||
file=sys.stderr)
|
||||
|
||||
def __await__(self):
|
||||
# Yield if the task is not finished
|
||||
|
|
|
@ -15,16 +15,18 @@
|
|||
from rclpy.clock import Clock
|
||||
from rclpy.clock import ClockType
|
||||
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
|
||||
from rclpy.utilities import get_default_context
|
||||
|
||||
|
||||
# TODO(mikaelarguedas) create a Timer or ROSTimer once we can specify custom time sources
|
||||
class WallTimer:
|
||||
|
||||
def __init__(self, callback, callback_group, timer_period_ns):
|
||||
def __init__(self, callback, callback_group, timer_period_ns, *, context=None):
|
||||
self._context = get_default_context() if context is None else context
|
||||
# TODO(sloretz) Allow passing clocks in via timer constructor
|
||||
self._clock = Clock(clock_type=ClockType.STEADY_TIME)
|
||||
[self.timer_handle, self.timer_pointer] = _rclpy.rclpy_create_timer(
|
||||
self._clock._clock_handle, timer_period_ns)
|
||||
self._clock._clock_handle, self._context.handle, timer_period_ns)
|
||||
self.timer_period_ns = timer_period_ns
|
||||
self.callback = callback
|
||||
self.callback_group = callback_group
|
||||
|
|
|
@ -16,9 +16,24 @@ import sys
|
|||
import threading
|
||||
|
||||
from rclpy.constants import S_TO_NS
|
||||
from rclpy.context import Context
|
||||
|
||||
g_default_context = None
|
||||
g_context_lock = threading.Lock()
|
||||
|
||||
|
||||
g_shutdown_lock = threading.Lock()
|
||||
def get_default_context(*, shutting_down=False):
|
||||
"""Return the global default context singleton."""
|
||||
global g_context_lock
|
||||
with g_context_lock:
|
||||
global g_default_context
|
||||
if g_default_context is None:
|
||||
g_default_context = Context()
|
||||
if shutting_down:
|
||||
old_context = g_default_context
|
||||
g_default_context = None
|
||||
return old_context
|
||||
return g_default_context
|
||||
|
||||
|
||||
def remove_ros_args(args=None):
|
||||
|
@ -28,27 +43,23 @@ def remove_ros_args(args=None):
|
|||
args if args is not None else sys.argv)
|
||||
|
||||
|
||||
def ok():
|
||||
# imported locally to avoid loading extensions on module import
|
||||
from rclpy.impl.implementation_singleton import rclpy_implementation
|
||||
with g_shutdown_lock:
|
||||
return rclpy_implementation.rclpy_ok()
|
||||
def ok(*, context=None):
|
||||
if context is None:
|
||||
context = get_default_context()
|
||||
return context.ok()
|
||||
|
||||
|
||||
def shutdown():
|
||||
# imported locally to avoid loading extensions on module import
|
||||
from rclpy.impl.implementation_singleton import rclpy_implementation
|
||||
with g_shutdown_lock:
|
||||
return rclpy_implementation.rclpy_shutdown()
|
||||
def shutdown(*, context=None):
|
||||
if context is None:
|
||||
context = get_default_context(shutting_down=True)
|
||||
return context.shutdown()
|
||||
|
||||
|
||||
def try_shutdown():
|
||||
def try_shutdown(*, context=None):
|
||||
"""Shutdown rclpy if not already shutdown."""
|
||||
# imported locally to avoid loading extensions on module import
|
||||
from rclpy.impl.implementation_singleton import rclpy_implementation
|
||||
with g_shutdown_lock:
|
||||
if rclpy_implementation.rclpy_ok():
|
||||
return rclpy_implementation.rclpy_shutdown()
|
||||
if context is None:
|
||||
context = get_default_context()
|
||||
return context.try_shutdown()
|
||||
|
||||
|
||||
def get_rmw_implementation_identifier():
|
||||
|
|
|
@ -76,6 +76,65 @@ static void * get_capsule_pointer(PyObject * pymetaclass, const char * attr)
|
|||
return ptr;
|
||||
}
|
||||
|
||||
void
|
||||
_rclpy_context_capsule_destructor(PyObject * capsule)
|
||||
{
|
||||
rcl_context_t * context = (rcl_context_t *)PyCapsule_GetPointer(capsule, "rcl_context_t");
|
||||
if (NULL == context) {
|
||||
return;
|
||||
}
|
||||
if (NULL != context->impl) {
|
||||
rcl_ret_t ret;
|
||||
if (rcl_context_is_valid(context)) {
|
||||
// shutdown first, if still valid
|
||||
ret = rcl_shutdown(context);
|
||||
if (RCL_RET_OK != ret) {
|
||||
fprintf(stderr,
|
||||
"[rclpy|" RCUTILS_STRINGIFY(__FILE__) ":" RCUTILS_STRINGIFY(__LINE__) "]: "
|
||||
"failed to shutdown rcl_context_t (%d) during PyCapsule destructor: %s\n",
|
||||
ret,
|
||||
rcl_get_error_string().str);
|
||||
rcl_reset_error();
|
||||
}
|
||||
}
|
||||
ret = rcl_context_fini(context);
|
||||
if (RCL_RET_OK != ret) {
|
||||
fprintf(stderr,
|
||||
"[rclpy|" RCUTILS_STRINGIFY(__FILE__) ":" RCUTILS_STRINGIFY(__LINE__) "]: "
|
||||
"failed to fini rcl_context_t (%d) during PyCapsule destructor: %s\n",
|
||||
ret,
|
||||
rcl_get_error_string().str);
|
||||
rcl_reset_error();
|
||||
}
|
||||
}
|
||||
PyMem_FREE(context);
|
||||
}
|
||||
|
||||
/// Create a rcl_context_t.
|
||||
/**
|
||||
* A successful call will return a Capsule with the pointer to the created
|
||||
* rcl_context_t structure.
|
||||
*
|
||||
* The returned context is zero-initialized for use with rclpy_init().
|
||||
*
|
||||
* Raises RuntimeError if creating the context fails.
|
||||
*
|
||||
* \return a list with the capsule and memory location, or
|
||||
* \return NULL on failure
|
||||
*/
|
||||
static PyObject *
|
||||
rclpy_create_context(PyObject * Py_UNUSED(self), PyObject * Py_UNUSED(args))
|
||||
{
|
||||
rcl_context_t * context = (rcl_context_t *)PyMem_Malloc(sizeof(rcl_context_t));
|
||||
if (NULL == context) {
|
||||
PyErr_Format(PyExc_MemoryError, "Failed to allocate memory for context");
|
||||
return NULL;
|
||||
}
|
||||
*context = rcl_get_zero_initialized_context();
|
||||
// if it fails, error is set and NULL is returned as it should
|
||||
return PyCapsule_New(context, "rcl_context_t", _rclpy_context_capsule_destructor);
|
||||
}
|
||||
|
||||
/// Create a sigint guard condition
|
||||
/**
|
||||
* A successful call will return a list with two elements:
|
||||
|
@ -89,14 +148,25 @@ static void * get_capsule_pointer(PyObject * pymetaclass, const char * attr)
|
|||
* \return NULL on failure
|
||||
*/
|
||||
static PyObject *
|
||||
rclpy_get_sigint_guard_condition(PyObject * Py_UNUSED(self), PyObject * Py_UNUSED(args))
|
||||
rclpy_get_sigint_guard_condition(PyObject * Py_UNUSED(self), PyObject * args)
|
||||
{
|
||||
PyObject * pycontext;
|
||||
|
||||
if (!PyArg_ParseTuple(args, "O", &pycontext)) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
rcl_context_t * context = (rcl_context_t *)PyCapsule_GetPointer(pycontext, "rcl_context_t");
|
||||
if (NULL == context) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
rcl_guard_condition_t * sigint_gc =
|
||||
(rcl_guard_condition_t *)PyMem_Malloc(sizeof(rcl_guard_condition_t));
|
||||
*sigint_gc = rcl_get_zero_initialized_guard_condition();
|
||||
rcl_guard_condition_options_t sigint_gc_options = rcl_guard_condition_get_default_options();
|
||||
|
||||
rcl_ret_t ret = rcl_guard_condition_init(sigint_gc, sigint_gc_options);
|
||||
rcl_ret_t ret = rcl_guard_condition_init(sigint_gc, context, sigint_gc_options);
|
||||
if (ret != RCL_RET_OK) {
|
||||
PyErr_Format(PyExc_RuntimeError,
|
||||
"Failed to create guard_condition: %s", rcl_get_error_string().str);
|
||||
|
@ -127,14 +197,25 @@ rclpy_get_sigint_guard_condition(PyObject * Py_UNUSED(self), PyObject * Py_UNUSE
|
|||
* \return NULL on failure
|
||||
*/
|
||||
static PyObject *
|
||||
rclpy_create_guard_condition(PyObject * Py_UNUSED(self), PyObject * Py_UNUSED(args))
|
||||
rclpy_create_guard_condition(PyObject * Py_UNUSED(self), PyObject * args)
|
||||
{
|
||||
PyObject * pycontext;
|
||||
|
||||
if (!PyArg_ParseTuple(args, "O", &pycontext)) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
rcl_context_t * context = (rcl_context_t *)PyCapsule_GetPointer(pycontext, "rcl_context_t");
|
||||
if (NULL == context) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
rcl_guard_condition_t * gc =
|
||||
(rcl_guard_condition_t *)PyMem_Malloc(sizeof(rcl_guard_condition_t));
|
||||
*gc = rcl_get_zero_initialized_guard_condition();
|
||||
rcl_guard_condition_options_t gc_options = rcl_guard_condition_get_default_options();
|
||||
|
||||
rcl_ret_t ret = rcl_guard_condition_init(gc, gc_options);
|
||||
rcl_ret_t ret = rcl_guard_condition_init(gc, context, gc_options);
|
||||
if (ret != RCL_RET_OK) {
|
||||
PyErr_Format(PyExc_RuntimeError,
|
||||
"Failed to create guard_condition: %s", rcl_get_error_string().str);
|
||||
|
@ -383,25 +464,34 @@ rclpy_remove_ros_args(PyObject * Py_UNUSED(self), PyObject * args)
|
|||
static PyObject *
|
||||
rclpy_init(PyObject * Py_UNUSED(self), PyObject * args)
|
||||
{
|
||||
// Expect one argument which is a list of strings
|
||||
// Expect two arguments, one is a list of strings and the other is a context.
|
||||
PyObject * pyargs;
|
||||
if (!PyArg_ParseTuple(args, "O", &pyargs)) {
|
||||
PyObject * pyseqlist;
|
||||
PyObject * pycontext;
|
||||
if (!PyArg_ParseTuple(args, "OO", &pyargs, &pycontext)) {
|
||||
// Exception raised
|
||||
return NULL;
|
||||
}
|
||||
|
||||
pyargs = PySequence_List(pyargs);
|
||||
if (NULL == pyargs) {
|
||||
pyseqlist = PySequence_List(pyargs);
|
||||
if (NULL == pyseqlist) {
|
||||
// Exception raised
|
||||
return NULL;
|
||||
}
|
||||
Py_ssize_t pysize_num_args = PyList_Size(pyargs);
|
||||
Py_ssize_t pysize_num_args = PyList_Size(pyseqlist);
|
||||
if (pysize_num_args > INT_MAX) {
|
||||
PyErr_Format(PyExc_OverflowError, "Too many arguments");
|
||||
Py_DECREF(pyseqlist);
|
||||
return NULL;
|
||||
}
|
||||
int num_args = (int)pysize_num_args;
|
||||
|
||||
rcl_context_t * context = (rcl_context_t *)PyCapsule_GetPointer(pycontext, "rcl_context_t");
|
||||
if (NULL == context) {
|
||||
Py_DECREF(pyseqlist);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
rcl_allocator_t allocator = rcl_get_default_allocator();
|
||||
const char ** arg_values = NULL;
|
||||
bool have_args = true;
|
||||
|
@ -409,13 +499,13 @@ rclpy_init(PyObject * Py_UNUSED(self), PyObject * args)
|
|||
arg_values = allocator.allocate(sizeof(char *) * num_args, allocator.state);
|
||||
if (NULL == arg_values) {
|
||||
PyErr_Format(PyExc_MemoryError, "Failed to allocate space for arguments");
|
||||
Py_DECREF(pyargs);
|
||||
Py_DECREF(pyseqlist);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
for (int i = 0; i < num_args; ++i) {
|
||||
// Returns borrowed reference, do not decref
|
||||
PyObject * pyarg = PyList_GetItem(pyargs, i);
|
||||
PyObject * pyarg = PyList_GetItem(pyseqlist, i);
|
||||
if (NULL == pyarg) {
|
||||
have_args = false;
|
||||
break;
|
||||
|
@ -426,10 +516,18 @@ rclpy_init(PyObject * Py_UNUSED(self), PyObject * args)
|
|||
}
|
||||
|
||||
if (have_args) {
|
||||
rcl_ret_t ret = rcl_init(num_args, arg_values, allocator);
|
||||
if (ret != RCL_RET_OK) {
|
||||
PyErr_Format(PyExc_RuntimeError, "Failed to init: %s", rcl_get_error_string().str);
|
||||
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
|
||||
rcl_ret_t ret = rcl_init_options_init(&init_options, allocator);
|
||||
if (RCL_RET_OK != ret) {
|
||||
PyErr_Format(
|
||||
PyExc_RuntimeError, "Failed to initialize init_options: %s", rcl_get_error_string().str);
|
||||
rcl_reset_error();
|
||||
} else {
|
||||
ret = rcl_init(num_args, arg_values, &init_options, context);
|
||||
if (ret != RCL_RET_OK) {
|
||||
PyErr_Format(PyExc_RuntimeError, "Failed to init: %s", rcl_get_error_string().str);
|
||||
rcl_reset_error();
|
||||
}
|
||||
}
|
||||
}
|
||||
if (NULL != arg_values) {
|
||||
|
@ -445,7 +543,7 @@ rclpy_init(PyObject * Py_UNUSED(self), PyObject * args)
|
|||
#pragma warning(pop)
|
||||
#endif
|
||||
}
|
||||
Py_DECREF(pyargs);
|
||||
Py_DECREF(pyseqlist);
|
||||
|
||||
// Register our signal handler that will forward to the original one.
|
||||
g_original_signal_handler = signal(SIGINT, catch_function);
|
||||
|
@ -473,15 +571,21 @@ rclpy_create_node(PyObject * Py_UNUSED(self), PyObject * args)
|
|||
rcl_ret_t ret;
|
||||
const char * node_name;
|
||||
const char * namespace_;
|
||||
PyObject * pycontext;
|
||||
PyObject * py_cli_args;
|
||||
int use_global_arguments;
|
||||
|
||||
if (
|
||||
!PyArg_ParseTuple(args, "ssOp", &node_name, &namespace_, &py_cli_args, &use_global_arguments))
|
||||
if (!PyArg_ParseTuple(
|
||||
args, "ssOOp", &node_name, &namespace_, &pycontext, &py_cli_args, &use_global_arguments))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
|
||||
rcl_context_t * context = (rcl_context_t *)PyCapsule_GetPointer(pycontext, "rcl_context_t");
|
||||
if (NULL == context) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
rcl_arguments_t arguments = rcl_get_zero_initialized_arguments();
|
||||
|
||||
ret = _rclpy_parse_args(py_cli_args, &arguments);
|
||||
|
@ -495,7 +599,7 @@ rclpy_create_node(PyObject * Py_UNUSED(self), PyObject * args)
|
|||
rcl_node_options_t options = rcl_node_get_default_options();
|
||||
options.use_global_arguments = use_global_arguments;
|
||||
options.arguments = arguments;
|
||||
ret = rcl_node_init(node, node_name, namespace_, &options);
|
||||
ret = rcl_node_init(node, node_name, namespace_, context, &options);
|
||||
if (ret != RCL_RET_OK) {
|
||||
if (ret == RCL_RET_BAD_ALLOC) {
|
||||
PyErr_Format(PyExc_MemoryError,
|
||||
|
@ -1194,8 +1298,14 @@ rclpy_create_timer(PyObject * Py_UNUSED(self), PyObject * args)
|
|||
{
|
||||
unsigned PY_LONG_LONG period_nsec;
|
||||
PyObject * pyclock;
|
||||
PyObject * pycontext;
|
||||
|
||||
if (!PyArg_ParseTuple(args, "OK", &pyclock, &period_nsec)) {
|
||||
if (!PyArg_ParseTuple(args, "OOK", &pyclock, &pycontext, &period_nsec)) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
rcl_context_t * context = (rcl_context_t *)PyCapsule_GetPointer(pycontext, "rcl_context_t");
|
||||
if (NULL == context) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
|
@ -1208,7 +1318,7 @@ rclpy_create_timer(PyObject * Py_UNUSED(self), PyObject * args)
|
|||
*timer = rcl_get_zero_initialized_timer();
|
||||
|
||||
rcl_allocator_t allocator = rcl_get_default_allocator();
|
||||
rcl_ret_t ret = rcl_timer_init(timer, clock, period_nsec, NULL, allocator);
|
||||
rcl_ret_t ret = rcl_timer_init(timer, clock, context, period_nsec, NULL, allocator);
|
||||
if (ret != RCL_RET_OK) {
|
||||
PyErr_Format(PyExc_RuntimeError,
|
||||
"Failed to create timer: %s", rcl_get_error_string().str);
|
||||
|
@ -2733,9 +2843,20 @@ rclpy_take_response(PyObject * Py_UNUSED(self), PyObject * args)
|
|||
* \return True if rcl is running properly, False otherwise
|
||||
*/
|
||||
static PyObject *
|
||||
rclpy_ok(PyObject * Py_UNUSED(self), PyObject * Py_UNUSED(args))
|
||||
rclpy_ok(PyObject * Py_UNUSED(self), PyObject * args)
|
||||
{
|
||||
bool ok = rcl_ok();
|
||||
PyObject * pycontext;
|
||||
|
||||
if (!PyArg_ParseTuple(args, "O", &pycontext)) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
rcl_context_t * context = (rcl_context_t *)PyCapsule_GetPointer(pycontext, "rcl_context_t");
|
||||
if (NULL == context) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
bool ok = rcl_context_is_valid(context);
|
||||
if (ok) {
|
||||
Py_RETURN_TRUE;
|
||||
} else {
|
||||
|
@ -2750,9 +2871,20 @@ rclpy_ok(PyObject * Py_UNUSED(self), PyObject * Py_UNUSED(args))
|
|||
* \return None
|
||||
*/
|
||||
static PyObject *
|
||||
rclpy_shutdown(PyObject * Py_UNUSED(self), PyObject * Py_UNUSED(args))
|
||||
rclpy_shutdown(PyObject * Py_UNUSED(self), PyObject * args)
|
||||
{
|
||||
rcl_ret_t ret = rcl_shutdown();
|
||||
PyObject * pycontext;
|
||||
|
||||
if (!PyArg_ParseTuple(args, "O", &pycontext)) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
rcl_context_t * context = (rcl_context_t *)PyCapsule_GetPointer(pycontext, "rcl_context_t");
|
||||
if (NULL == context) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
rcl_ret_t ret = rcl_shutdown(context);
|
||||
if (ret != RCL_RET_OK) {
|
||||
PyErr_Format(PyExc_RuntimeError,
|
||||
"Failed to shutdown: %s", rcl_get_error_string().str);
|
||||
|
@ -3936,8 +4068,9 @@ rclpy_get_node_parameters(PyObject * Py_UNUSED(self), PyObject * args)
|
|||
const rcl_allocator_t allocator = node_options->allocator;
|
||||
|
||||
if (node_options->use_global_arguments) {
|
||||
if (!_parse_param_files(rcl_get_global_arguments(), allocator, parameter_cls,
|
||||
parameter_type_cls, params_by_node_name))
|
||||
if (!_parse_param_files(
|
||||
&(node->context->global_arguments), allocator, parameter_cls,
|
||||
parameter_type_cls, params_by_node_name))
|
||||
{
|
||||
Py_DECREF(parameter_type_cls);
|
||||
Py_DECREF(params_by_node_name);
|
||||
|
@ -3992,13 +4125,17 @@ rclpy_get_node_parameters(PyObject * Py_UNUSED(self), PyObject * args)
|
|||
|
||||
/// Define the public methods of this module
|
||||
static PyMethodDef rclpy_methods[] = {
|
||||
{
|
||||
"rclpy_create_context", rclpy_create_context, METH_VARARGS,
|
||||
"Create a rcl context."
|
||||
},
|
||||
{
|
||||
"rclpy_init", rclpy_init, METH_VARARGS,
|
||||
"Initialize RCL."
|
||||
},
|
||||
{
|
||||
"rclpy_remove_ros_args", rclpy_remove_ros_args, METH_VARARGS,
|
||||
"Remove ROS-specific arguments from argument vector"
|
||||
"Remove ROS-specific arguments from argument vector."
|
||||
},
|
||||
{
|
||||
"rclpy_create_node", rclpy_create_node, METH_VARARGS,
|
||||
|
@ -4070,7 +4207,7 @@ static PyMethodDef rclpy_methods[] = {
|
|||
},
|
||||
|
||||
{
|
||||
"rclpy_get_sigint_guard_condition", rclpy_get_sigint_guard_condition, METH_NOARGS,
|
||||
"rclpy_get_sigint_guard_condition", rclpy_get_sigint_guard_condition, METH_VARARGS,
|
||||
"Create a guard_condition triggered when sigint is received."
|
||||
},
|
||||
{
|
||||
|
@ -4210,12 +4347,12 @@ static PyMethodDef rclpy_methods[] = {
|
|||
},
|
||||
|
||||
{
|
||||
"rclpy_ok", rclpy_ok, METH_NOARGS,
|
||||
"rclpy_ok", rclpy_ok, METH_VARARGS,
|
||||
"rclpy_ok."
|
||||
},
|
||||
|
||||
{
|
||||
"rclpy_shutdown", rclpy_shutdown, METH_NOARGS,
|
||||
"rclpy_shutdown", rclpy_shutdown, METH_VARARGS,
|
||||
"rclpy_shutdown."
|
||||
},
|
||||
|
||||
|
|
|
@ -25,13 +25,14 @@ class TestCallbackGroup(unittest.TestCase):
|
|||
|
||||
@classmethod
|
||||
def setUpClass(cls):
|
||||
rclpy.init()
|
||||
cls.node = rclpy.create_node('TestCallbackGroup', namespace='/rclpy')
|
||||
cls.context = rclpy.context.Context()
|
||||
rclpy.init(context=cls.context)
|
||||
cls.node = rclpy.create_node('TestCallbackGroup', namespace='/rclpy', context=cls.context)
|
||||
|
||||
@classmethod
|
||||
def tearDownClass(cls):
|
||||
cls.node.destroy_node()
|
||||
rclpy.shutdown()
|
||||
rclpy.shutdown(context=cls.context)
|
||||
|
||||
def test_reentrant_group(self):
|
||||
self.assertIsNotNone(self.node.handle)
|
||||
|
|
|
@ -17,6 +17,7 @@ import unittest
|
|||
|
||||
from rcl_interfaces.srv import GetParameters
|
||||
import rclpy
|
||||
import rclpy.executors
|
||||
|
||||
|
||||
# TODO(sloretz) Reduce fudge once wait_for_service uses node graph events
|
||||
|
@ -27,13 +28,14 @@ class TestClient(unittest.TestCase):
|
|||
|
||||
@classmethod
|
||||
def setUpClass(cls):
|
||||
rclpy.init()
|
||||
cls.node = rclpy.create_node('TestClient')
|
||||
cls.context = rclpy.context.Context()
|
||||
rclpy.init(context=cls.context)
|
||||
cls.node = rclpy.create_node('TestClient', context=cls.context)
|
||||
|
||||
@classmethod
|
||||
def tearDownClass(cls):
|
||||
cls.node.destroy_node()
|
||||
rclpy.shutdown()
|
||||
rclpy.shutdown(context=cls.context)
|
||||
|
||||
def test_wait_for_service_5sec(self):
|
||||
cli = self.node.create_client(GetParameters, 'get/parameters')
|
||||
|
@ -79,8 +81,9 @@ class TestClient(unittest.TestCase):
|
|||
self.assertTrue(cli.wait_for_service(timeout_sec=20))
|
||||
future1 = cli.call_async(GetParameters.Request())
|
||||
future2 = cli.call_async(GetParameters.Request())
|
||||
rclpy.spin_until_future_complete(self.node, future1)
|
||||
rclpy.spin_until_future_complete(self.node, future2)
|
||||
executor = rclpy.executors.SingleThreadedExecutor(context=self.context)
|
||||
rclpy.spin_until_future_complete(self.node, future1, executor=executor)
|
||||
rclpy.spin_until_future_complete(self.node, future2, executor=executor)
|
||||
self.assertTrue(future1.result() is not None)
|
||||
self.assertTrue(future2.result() is not None)
|
||||
finally:
|
||||
|
|
|
@ -24,51 +24,52 @@ class TestCreateNode(unittest.TestCase):
|
|||
|
||||
@classmethod
|
||||
def setUpClass(cls):
|
||||
rclpy.init()
|
||||
cls.context = rclpy.context.Context()
|
||||
rclpy.init(context=cls.context)
|
||||
|
||||
@classmethod
|
||||
def tearDownClass(cls):
|
||||
rclpy.shutdown()
|
||||
rclpy.shutdown(context=cls.context)
|
||||
|
||||
def test_create_node(self):
|
||||
node_name = 'create_node_test'
|
||||
rclpy.create_node(node_name).destroy_node()
|
||||
rclpy.create_node(node_name, context=self.context).destroy_node()
|
||||
|
||||
def test_create_node_with_namespace(self):
|
||||
node_name = 'create_node_test'
|
||||
namespace = '/ns'
|
||||
rclpy.create_node(node_name, namespace=namespace).destroy_node()
|
||||
rclpy.create_node(node_name, namespace=namespace, context=self.context).destroy_node()
|
||||
|
||||
def test_create_node_with_empty_namespace(self):
|
||||
node_name = 'create_node_test'
|
||||
namespace = ''
|
||||
node = rclpy.create_node(node_name, namespace=namespace)
|
||||
node = rclpy.create_node(node_name, namespace=namespace, context=self.context)
|
||||
self.assertEqual('/', node.get_namespace())
|
||||
node.destroy_node()
|
||||
|
||||
def test_create_node_with_relative_namespace(self):
|
||||
node_name = 'create_node_test'
|
||||
namespace = 'ns'
|
||||
node = rclpy.create_node(node_name, namespace=namespace)
|
||||
node = rclpy.create_node(node_name, namespace=namespace, context=self.context)
|
||||
self.assertEqual('/ns', node.get_namespace())
|
||||
node.destroy_node()
|
||||
|
||||
def test_create_node_invalid_name(self):
|
||||
node_name = 'create_node_test_invalid_name?'
|
||||
with self.assertRaisesRegex(InvalidNodeNameException, 'must not contain characters'):
|
||||
rclpy.create_node(node_name)
|
||||
rclpy.create_node(node_name, context=self.context)
|
||||
|
||||
def test_create_node_invalid_relative_namespace(self):
|
||||
node_name = 'create_node_test_invalid_namespace'
|
||||
namespace = 'invalid_namespace?'
|
||||
with self.assertRaisesRegex(InvalidNamespaceException, 'must not contain characters'):
|
||||
rclpy.create_node(node_name, namespace=namespace)
|
||||
rclpy.create_node(node_name, namespace=namespace, context=self.context)
|
||||
|
||||
def test_create_node_invalid_namespace(self):
|
||||
node_name = 'create_node_test_invalid_namespace'
|
||||
namespace = '/invalid_namespace?'
|
||||
with self.assertRaisesRegex(InvalidNamespaceException, 'must not contain characters'):
|
||||
rclpy.create_node(node_name, namespace=namespace)
|
||||
rclpy.create_node(node_name, namespace=namespace, context=self.context)
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
|
|
|
@ -28,22 +28,24 @@ def run_catch_report_raise(func, *args, **kwargs):
|
|||
|
||||
def func_destroy_node():
|
||||
import rclpy
|
||||
rclpy.init()
|
||||
node = rclpy.create_node('test_node1')
|
||||
context = rclpy.context.Context()
|
||||
rclpy.init(context=context)
|
||||
node = rclpy.create_node('test_node1', context=context)
|
||||
ret = True
|
||||
try:
|
||||
node.destroy_node()
|
||||
except RuntimeError:
|
||||
ret = False
|
||||
finally:
|
||||
rclpy.shutdown()
|
||||
rclpy.shutdown(context=context)
|
||||
return ret
|
||||
|
||||
|
||||
def func_destroy_node_twice():
|
||||
import rclpy
|
||||
rclpy.init()
|
||||
node = rclpy.create_node('test_node2')
|
||||
context = rclpy.context.Context()
|
||||
rclpy.init(context=context)
|
||||
node = rclpy.create_node('test_node2', context=context)
|
||||
assert node.destroy_node() is True
|
||||
assert node.destroy_node() is True
|
||||
return True
|
||||
|
@ -51,8 +53,9 @@ def func_destroy_node_twice():
|
|||
|
||||
def func_destroy_corrupted_node():
|
||||
import rclpy
|
||||
rclpy.init()
|
||||
node = rclpy.create_node('test_node2')
|
||||
context = rclpy.context.Context()
|
||||
rclpy.init(context=context)
|
||||
node = rclpy.create_node('test_node2', context=context)
|
||||
assert node.destroy_node() is True
|
||||
org_handle = node._handle
|
||||
node._handle = 'garbage'
|
||||
|
@ -64,15 +67,16 @@ def func_destroy_corrupted_node():
|
|||
node._handle = org_handle
|
||||
node.destroy_node()
|
||||
finally:
|
||||
rclpy.shutdown()
|
||||
rclpy.shutdown(context=context)
|
||||
return ret
|
||||
|
||||
|
||||
def func_destroy_timers():
|
||||
import rclpy
|
||||
rclpy.init()
|
||||
context = rclpy.context.Context()
|
||||
rclpy.init(context=context)
|
||||
|
||||
node = rclpy.create_node('test_node3')
|
||||
node = rclpy.create_node('test_node3', context=context)
|
||||
|
||||
timer1 = node.create_timer(0.1, None)
|
||||
timer2 = node.create_timer(1, None)
|
||||
|
@ -92,16 +96,17 @@ def func_destroy_timers():
|
|||
assert node.handle is None
|
||||
ret = True
|
||||
finally:
|
||||
rclpy.shutdown()
|
||||
rclpy.shutdown(context=context)
|
||||
return ret
|
||||
|
||||
|
||||
def func_destroy_entities():
|
||||
import rclpy
|
||||
from test_msgs.msg import Primitives
|
||||
rclpy.init()
|
||||
context = rclpy.context.Context()
|
||||
rclpy.init(context=context)
|
||||
|
||||
node = rclpy.create_node('test_node4')
|
||||
node = rclpy.create_node('test_node4', context=context)
|
||||
|
||||
timer = node.create_timer(0.1, None)
|
||||
timer # noqa
|
||||
|
@ -136,14 +141,15 @@ def func_destroy_entities():
|
|||
assert node.handle is None
|
||||
ret = True
|
||||
finally:
|
||||
rclpy.shutdown()
|
||||
rclpy.shutdown(context=context)
|
||||
return ret
|
||||
|
||||
|
||||
def func_corrupt_node_handle():
|
||||
import rclpy
|
||||
rclpy.init()
|
||||
node = rclpy.create_node('test_node5')
|
||||
context = rclpy.context.Context()
|
||||
rclpy.init(context=context)
|
||||
node = rclpy.create_node('test_node5', context=context)
|
||||
try:
|
||||
node.handle = 'garbage'
|
||||
ret = False
|
||||
|
@ -151,7 +157,7 @@ def func_corrupt_node_handle():
|
|||
node.destroy_node()
|
||||
ret = True
|
||||
finally:
|
||||
rclpy.shutdown()
|
||||
rclpy.shutdown(context=context)
|
||||
return ret
|
||||
|
||||
|
||||
|
|
|
@ -24,12 +24,13 @@ from rclpy.executors import SingleThreadedExecutor
|
|||
class TestExecutor(unittest.TestCase):
|
||||
|
||||
def setUp(self):
|
||||
rclpy.init()
|
||||
self.node = rclpy.create_node('TestExecutor', namespace='/rclpy')
|
||||
self.context = rclpy.context.Context()
|
||||
rclpy.init(context=self.context)
|
||||
self.node = rclpy.create_node('TestExecutor', namespace='/rclpy', context=self.context)
|
||||
|
||||
def tearDown(self):
|
||||
self.node.destroy_node()
|
||||
rclpy.shutdown()
|
||||
rclpy.shutdown(context=self.context)
|
||||
|
||||
def func_execution(self, executor):
|
||||
got_callback = False
|
||||
|
@ -51,7 +52,7 @@ class TestExecutor(unittest.TestCase):
|
|||
|
||||
def test_single_threaded_executor_executes(self):
|
||||
self.assertIsNotNone(self.node.handle)
|
||||
executor = SingleThreadedExecutor()
|
||||
executor = SingleThreadedExecutor(context=self.context)
|
||||
try:
|
||||
self.assertTrue(self.func_execution(executor))
|
||||
finally:
|
||||
|
@ -59,7 +60,7 @@ class TestExecutor(unittest.TestCase):
|
|||
|
||||
def test_remove_node(self):
|
||||
self.assertIsNotNone(self.node.handle)
|
||||
executor = SingleThreadedExecutor()
|
||||
executor = SingleThreadedExecutor(context=self.context)
|
||||
|
||||
got_callback = False
|
||||
|
||||
|
@ -82,7 +83,7 @@ class TestExecutor(unittest.TestCase):
|
|||
|
||||
def test_multi_threaded_executor_executes(self):
|
||||
self.assertIsNotNone(self.node.handle)
|
||||
executor = MultiThreadedExecutor()
|
||||
executor = MultiThreadedExecutor(context=self.context)
|
||||
try:
|
||||
self.assertTrue(self.func_execution(executor))
|
||||
finally:
|
||||
|
@ -90,13 +91,13 @@ class TestExecutor(unittest.TestCase):
|
|||
|
||||
def test_add_node_to_executor(self):
|
||||
self.assertIsNotNone(self.node.handle)
|
||||
executor = SingleThreadedExecutor()
|
||||
executor = SingleThreadedExecutor(context=self.context)
|
||||
executor.add_node(self.node)
|
||||
self.assertIn(self.node, executor.get_nodes())
|
||||
|
||||
def test_executor_spin_non_blocking(self):
|
||||
self.assertIsNotNone(self.node.handle)
|
||||
executor = SingleThreadedExecutor()
|
||||
executor = SingleThreadedExecutor(context=self.context)
|
||||
executor.add_node(self.node)
|
||||
start = time.monotonic()
|
||||
executor.spin_once(timeout_sec=0)
|
||||
|
@ -105,7 +106,7 @@ class TestExecutor(unittest.TestCase):
|
|||
|
||||
def test_execute_coroutine_timer(self):
|
||||
self.assertIsNotNone(self.node.handle)
|
||||
executor = SingleThreadedExecutor()
|
||||
executor = SingleThreadedExecutor(context=self.context)
|
||||
executor.add_node(self.node)
|
||||
|
||||
called1 = False
|
||||
|
@ -133,7 +134,7 @@ class TestExecutor(unittest.TestCase):
|
|||
|
||||
def test_execute_coroutine_guard_condition(self):
|
||||
self.assertIsNotNone(self.node.handle)
|
||||
executor = SingleThreadedExecutor()
|
||||
executor = SingleThreadedExecutor(context=self.context)
|
||||
executor.add_node(self.node)
|
||||
|
||||
called1 = False
|
||||
|
@ -162,7 +163,7 @@ class TestExecutor(unittest.TestCase):
|
|||
|
||||
def test_create_task_coroutine(self):
|
||||
self.assertIsNotNone(self.node.handle)
|
||||
executor = SingleThreadedExecutor()
|
||||
executor = SingleThreadedExecutor(context=self.context)
|
||||
executor.add_node(self.node)
|
||||
|
||||
async def coroutine():
|
||||
|
@ -177,7 +178,7 @@ class TestExecutor(unittest.TestCase):
|
|||
|
||||
def test_create_task_normal_function(self):
|
||||
self.assertIsNotNone(self.node.handle)
|
||||
executor = SingleThreadedExecutor()
|
||||
executor = SingleThreadedExecutor(context=self.context)
|
||||
executor.add_node(self.node)
|
||||
|
||||
def func():
|
||||
|
@ -192,7 +193,7 @@ class TestExecutor(unittest.TestCase):
|
|||
|
||||
def test_create_task_dependent_coroutines(self):
|
||||
self.assertIsNotNone(self.node.handle)
|
||||
executor = SingleThreadedExecutor()
|
||||
executor = SingleThreadedExecutor(context=self.context)
|
||||
executor.add_node(self.node)
|
||||
|
||||
async def coro1():
|
||||
|
@ -245,17 +246,18 @@ class TestExecutor(unittest.TestCase):
|
|||
|
||||
timer = self.node.create_timer(0.1, timer_callback)
|
||||
|
||||
rclpy.spin_once(self.node, timeout_sec=0.5)
|
||||
executor = SingleThreadedExecutor(context=self.context)
|
||||
rclpy.spin_once(self.node, timeout_sec=0.5, executor=executor)
|
||||
self.assertTrue(did_callback)
|
||||
|
||||
timer.cancel()
|
||||
trigger.do_yield = False
|
||||
rclpy.spin_once(self.node, timeout_sec=0)
|
||||
rclpy.spin_once(self.node, timeout_sec=0, executor=executor)
|
||||
self.assertTrue(did_return)
|
||||
|
||||
def test_executor_add_node(self):
|
||||
self.assertIsNotNone(self.node.handle)
|
||||
executor = SingleThreadedExecutor()
|
||||
executor = SingleThreadedExecutor(context=self.context)
|
||||
assert executor.add_node(self.node)
|
||||
assert not executor.add_node(self.node)
|
||||
|
||||
|
|
|
@ -22,16 +22,18 @@ class TestGuardCondition(unittest.TestCase):
|
|||
|
||||
@classmethod
|
||||
def setUpClass(cls):
|
||||
rclpy.init()
|
||||
cls.node = rclpy.create_node('TestGuardCondition', namespace='/rclpy/test')
|
||||
cls.executor = SingleThreadedExecutor()
|
||||
cls.context = rclpy.context.Context()
|
||||
rclpy.init(context=cls.context)
|
||||
cls.node = rclpy.create_node(
|
||||
'TestGuardCondition', namespace='/rclpy/test', context=cls.context)
|
||||
cls.executor = SingleThreadedExecutor(context=cls.context)
|
||||
cls.executor.add_node(cls.node)
|
||||
|
||||
@classmethod
|
||||
def tearDownClass(cls):
|
||||
cls.executor.shutdown()
|
||||
cls.node.destroy_node()
|
||||
rclpy.shutdown()
|
||||
rclpy.shutdown(context=cls.context)
|
||||
|
||||
def test_trigger(self):
|
||||
called = False
|
||||
|
|
|
@ -28,20 +28,22 @@ def run_catch_report_raise(func, *args, **kwargs):
|
|||
|
||||
def func_init():
|
||||
import rclpy
|
||||
context = rclpy.context.Context()
|
||||
try:
|
||||
rclpy.init()
|
||||
rclpy.init(context=context)
|
||||
except RuntimeError:
|
||||
return False
|
||||
|
||||
rclpy.shutdown()
|
||||
rclpy.shutdown(context=context)
|
||||
return True
|
||||
|
||||
|
||||
def func_init_shutdown():
|
||||
import rclpy
|
||||
context = rclpy.context.Context()
|
||||
try:
|
||||
rclpy.init()
|
||||
rclpy.shutdown()
|
||||
rclpy.init(context=context)
|
||||
rclpy.shutdown(context=context)
|
||||
return True
|
||||
except RuntimeError:
|
||||
return False
|
||||
|
@ -49,11 +51,21 @@ def func_init_shutdown():
|
|||
|
||||
def func_init_shutdown_sequence():
|
||||
import rclpy
|
||||
rclpy.init()
|
||||
rclpy.shutdown()
|
||||
try:
|
||||
# local
|
||||
context = rclpy.context.Context()
|
||||
rclpy.init(context=context)
|
||||
rclpy.shutdown(context=context)
|
||||
context = rclpy.context.Context() # context cannot be reused but should not interfere
|
||||
rclpy.init(context=context)
|
||||
rclpy.shutdown(context=context)
|
||||
|
||||
# global
|
||||
rclpy.init()
|
||||
rclpy.shutdown()
|
||||
rclpy.init()
|
||||
rclpy.shutdown()
|
||||
|
||||
return True
|
||||
except RuntimeError:
|
||||
return False
|
||||
|
@ -61,22 +73,24 @@ def func_init_shutdown_sequence():
|
|||
|
||||
def func_double_init():
|
||||
import rclpy
|
||||
rclpy.init()
|
||||
context = rclpy.context.Context()
|
||||
rclpy.init(context=context)
|
||||
try:
|
||||
rclpy.init()
|
||||
rclpy.init(context=context)
|
||||
except RuntimeError:
|
||||
rclpy.shutdown()
|
||||
return True
|
||||
rclpy.shutdown()
|
||||
finally:
|
||||
rclpy.shutdown(context=context)
|
||||
return False
|
||||
|
||||
|
||||
def func_double_shutdown():
|
||||
import rclpy
|
||||
rclpy.init()
|
||||
rclpy.shutdown()
|
||||
context = rclpy.context.Context()
|
||||
rclpy.init(context=context)
|
||||
rclpy.shutdown(context=context)
|
||||
try:
|
||||
rclpy.shutdown()
|
||||
rclpy.shutdown(context=context)
|
||||
except RuntimeError:
|
||||
return True
|
||||
|
||||
|
@ -86,8 +100,9 @@ def func_double_shutdown():
|
|||
def func_create_node_without_init():
|
||||
import rclpy
|
||||
from rclpy.exceptions import NotInitializedException
|
||||
context = rclpy.context.Context()
|
||||
try:
|
||||
rclpy.create_node('foo')
|
||||
rclpy.create_node('foo', context=context)
|
||||
except NotInitializedException:
|
||||
return True
|
||||
return False
|
||||
|
|
|
@ -32,13 +32,14 @@ class TestNode(unittest.TestCase):
|
|||
|
||||
@classmethod
|
||||
def setUpClass(cls):
|
||||
rclpy.init()
|
||||
cls.node = rclpy.create_node(TEST_NODE, namespace=TEST_NAMESPACE)
|
||||
cls.context = rclpy.context.Context()
|
||||
rclpy.init(context=cls.context)
|
||||
cls.node = rclpy.create_node(TEST_NODE, namespace=TEST_NAMESPACE, context=cls.context)
|
||||
|
||||
@classmethod
|
||||
def tearDownClass(cls):
|
||||
cls.node.destroy_node()
|
||||
rclpy.shutdown()
|
||||
rclpy.shutdown(context=cls.context)
|
||||
|
||||
def test_accessors(self):
|
||||
self.assertIsNotNone(self.node.handle)
|
||||
|
@ -136,14 +137,14 @@ class TestNode(unittest.TestCase):
|
|||
node_logger.debug('test')
|
||||
|
||||
def test_initially_no_executor(self):
|
||||
node = rclpy.create_node('my_node')
|
||||
node = rclpy.create_node('my_node', context=self.context)
|
||||
try:
|
||||
assert node.executor is None
|
||||
finally:
|
||||
node.destroy_node()
|
||||
|
||||
def test_set_executor_adds_node_to_it(self):
|
||||
node = rclpy.create_node('my_node')
|
||||
node = rclpy.create_node('my_node', context=self.context)
|
||||
executor = Mock()
|
||||
executor.add_node.return_value = True
|
||||
try:
|
||||
|
@ -154,7 +155,7 @@ class TestNode(unittest.TestCase):
|
|||
executor.add_node.assert_called_once_with(node)
|
||||
|
||||
def test_set_executor_removes_node_from_old_executor(self):
|
||||
node = rclpy.create_node('my_node')
|
||||
node = rclpy.create_node('my_node', context=self.context)
|
||||
old_executor = Mock()
|
||||
old_executor.add_node.return_value = True
|
||||
new_executor = Mock()
|
||||
|
@ -170,7 +171,7 @@ class TestNode(unittest.TestCase):
|
|||
new_executor.remove_node.assert_not_called()
|
||||
|
||||
def test_set_executor_clear_executor(self):
|
||||
node = rclpy.create_node('my_node')
|
||||
node = rclpy.create_node('my_node', context=self.context)
|
||||
executor = Mock()
|
||||
executor.add_node.return_value = True
|
||||
try:
|
||||
|
@ -249,25 +250,30 @@ class TestNode(unittest.TestCase):
|
|||
class TestCreateNode(unittest.TestCase):
|
||||
|
||||
def test_use_global_arguments(self):
|
||||
rclpy.init(args=['process_name', '__node:=global_node_name'])
|
||||
context = rclpy.context.Context()
|
||||
rclpy.init(args=['process_name', '__node:=global_node_name'], context=context)
|
||||
try:
|
||||
node1 = rclpy.create_node('my_node', namespace='/my_ns', use_global_arguments=True)
|
||||
node2 = rclpy.create_node('my_node', namespace='/my_ns', use_global_arguments=False)
|
||||
node1 = rclpy.create_node(
|
||||
'my_node', namespace='/my_ns', use_global_arguments=True, context=context)
|
||||
node2 = rclpy.create_node(
|
||||
'my_node', namespace='/my_ns', use_global_arguments=False, context=context)
|
||||
self.assertEqual('global_node_name', node1.get_name())
|
||||
self.assertEqual('my_node', node2.get_name())
|
||||
node1.destroy_node()
|
||||
node2.destroy_node()
|
||||
finally:
|
||||
rclpy.shutdown()
|
||||
rclpy.shutdown(context=context)
|
||||
|
||||
def test_node_arguments(self):
|
||||
rclpy.init()
|
||||
context = rclpy.context.Context()
|
||||
rclpy.init(context=context)
|
||||
try:
|
||||
node = rclpy.create_node('my_node', namespace='/my_ns', cli_args=['__ns:=/foo/bar'])
|
||||
node = rclpy.create_node(
|
||||
'my_node', namespace='/my_ns', cli_args=['__ns:=/foo/bar'], context=context)
|
||||
self.assertEqual('/foo/bar', node.get_namespace())
|
||||
node.destroy_node()
|
||||
finally:
|
||||
rclpy.shutdown()
|
||||
rclpy.shutdown(context=context)
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
|
|
|
@ -23,14 +23,15 @@ class TestParametersCallback(unittest.TestCase):
|
|||
|
||||
@classmethod
|
||||
def setUpClass(cls):
|
||||
rclpy.init()
|
||||
cls.context = rclpy.context.Context()
|
||||
rclpy.init(context=cls.context)
|
||||
|
||||
@classmethod
|
||||
def tearDownClass(cls):
|
||||
rclpy.shutdown()
|
||||
rclpy.shutdown(context=cls.context)
|
||||
|
||||
def setUp(self):
|
||||
self.node = rclpy.create_node('parameters_callback_node')
|
||||
self.node = rclpy.create_node('parameters_callback_node', context=self.context)
|
||||
|
||||
def tearDown(self):
|
||||
self.node.destroy_node()
|
||||
|
|
|
@ -34,22 +34,24 @@ from .mock_compat import __name__ as _ # noqa: ignore=F401
|
|||
class TestTimeSource(unittest.TestCase):
|
||||
|
||||
def setUp(self):
|
||||
rclpy.init()
|
||||
self.node = rclpy.create_node('TestTimeSource', namespace='/rclpy')
|
||||
self.context = rclpy.context.Context()
|
||||
rclpy.init(context=self.context)
|
||||
self.node = rclpy.create_node('TestTimeSource', namespace='/rclpy', context=self.context)
|
||||
|
||||
def tearDown(self):
|
||||
self.node.destroy_node()
|
||||
rclpy.shutdown()
|
||||
rclpy.shutdown(context=self.context)
|
||||
|
||||
def publish_clock_messages(self):
|
||||
clock_pub = self.node.create_publisher(builtin_interfaces.msg.Time, CLOCK_TOPIC)
|
||||
cycle_count = 0
|
||||
time_msg = builtin_interfaces.msg.Time()
|
||||
while rclpy.ok() and cycle_count < 5:
|
||||
while rclpy.ok(context=self.context) and cycle_count < 5:
|
||||
time_msg.sec = cycle_count
|
||||
clock_pub.publish(time_msg)
|
||||
cycle_count += 1
|
||||
rclpy.spin_once(self.node, timeout_sec=1)
|
||||
executor = rclpy.executors.SingleThreadedExecutor(context=self.context)
|
||||
rclpy.spin_once(self.node, timeout_sec=1, executor=executor)
|
||||
# TODO(dhood): use rate once available
|
||||
time.sleep(1)
|
||||
|
||||
|
@ -57,11 +59,12 @@ class TestTimeSource(unittest.TestCase):
|
|||
clock_pub = self.node.create_publisher(builtin_interfaces.msg.Time, CLOCK_TOPIC)
|
||||
cycle_count = 0
|
||||
time_msg = builtin_interfaces.msg.Time()
|
||||
while rclpy.ok() and cycle_count < 5:
|
||||
while rclpy.ok(context=self.context) and cycle_count < 5:
|
||||
time_msg.sec = 6 - cycle_count
|
||||
clock_pub.publish(time_msg)
|
||||
cycle_count += 1
|
||||
rclpy.spin_once(self.node, timeout_sec=1)
|
||||
executor = rclpy.executors.SingleThreadedExecutor(context=self.context)
|
||||
rclpy.spin_once(self.node, timeout_sec=1, executor=executor)
|
||||
time.sleep(1)
|
||||
|
||||
def test_time_source_attach_clock(self):
|
||||
|
@ -135,7 +138,7 @@ class TestTimeSource(unittest.TestCase):
|
|||
|
||||
# Check detaching the node
|
||||
time_source.detach_node()
|
||||
node2 = rclpy.create_node('TestTimeSource2', namespace='/rclpy')
|
||||
node2 = rclpy.create_node('TestTimeSource2', namespace='/rclpy', context=self.context)
|
||||
time_source.attach_node(node2)
|
||||
node2.destroy_node()
|
||||
assert time_source._node == node2
|
||||
|
|
|
@ -38,9 +38,10 @@ def run_catch_report_raise(func, *args, **kwargs):
|
|||
def func_zero_callback(args):
|
||||
period = float(args[0])
|
||||
|
||||
rclpy.init()
|
||||
node = rclpy.create_node('test_timer_no_callback')
|
||||
executor = SingleThreadedExecutor()
|
||||
context = rclpy.context.Context()
|
||||
rclpy.init(context=context)
|
||||
node = rclpy.create_node('test_timer_no_callback', context=context)
|
||||
executor = SingleThreadedExecutor(context=context)
|
||||
executor.add_node(node)
|
||||
# The first spin_once() takes slighly longer, just long enough for 1ms timer tests to fail
|
||||
executor.spin_once(timeout_sec=0)
|
||||
|
@ -51,7 +52,7 @@ def func_zero_callback(args):
|
|||
|
||||
node.destroy_timer(timer)
|
||||
executor.shutdown()
|
||||
rclpy.shutdown()
|
||||
rclpy.shutdown(context=context)
|
||||
assert len(callbacks) == 0, \
|
||||
"shouldn't have received any callback, received %d" % len(callbacks)
|
||||
|
||||
|
@ -61,9 +62,10 @@ def func_zero_callback(args):
|
|||
def func_number_callbacks(args):
|
||||
period = float(args[0])
|
||||
|
||||
rclpy.init()
|
||||
node = rclpy.create_node('test_timer_no_callback')
|
||||
executor = SingleThreadedExecutor()
|
||||
context = rclpy.context.Context()
|
||||
rclpy.init(context=context)
|
||||
node = rclpy.create_node('test_timer_no_callback', context=context)
|
||||
executor = SingleThreadedExecutor(context=context)
|
||||
executor.add_node(node)
|
||||
# The first spin_once() takes slighly longer, just long enough for 1ms timer tests to fail
|
||||
executor.spin_once(timeout_sec=0)
|
||||
|
@ -72,12 +74,12 @@ def func_number_callbacks(args):
|
|||
timer = node.create_timer(period, lambda: callbacks.append(len(callbacks)))
|
||||
begin_time = time.time()
|
||||
|
||||
while rclpy.ok() and time.time() - begin_time < 4.5 * period:
|
||||
while rclpy.ok(context=context) and time.time() - begin_time < 4.5 * period:
|
||||
executor.spin_once(timeout_sec=period / 10)
|
||||
|
||||
node.destroy_timer(timer)
|
||||
executor.shutdown()
|
||||
rclpy.shutdown()
|
||||
rclpy.shutdown(context=context)
|
||||
assert len(callbacks) == 4, 'should have received 4 callbacks, received %s' % str(callbacks)
|
||||
|
||||
return True
|
||||
|
@ -86,9 +88,10 @@ def func_number_callbacks(args):
|
|||
def func_cancel_reset_timer(args):
|
||||
period = float(args[0])
|
||||
|
||||
rclpy.init()
|
||||
node = rclpy.create_node('test_timer_no_callback')
|
||||
executor = SingleThreadedExecutor()
|
||||
context = rclpy.context.Context()
|
||||
rclpy.init(context=context)
|
||||
node = rclpy.create_node('test_timer_no_callback', context=context)
|
||||
executor = SingleThreadedExecutor(context=context)
|
||||
executor.add_node(node)
|
||||
# The first spin_once() takes slighly longer, just long enough for 1ms timer tests to fail
|
||||
executor.spin_once(timeout_sec=0)
|
||||
|
@ -99,7 +102,7 @@ def func_cancel_reset_timer(args):
|
|||
|
||||
assert not timer.is_canceled()
|
||||
|
||||
while rclpy.ok() and time.time() - begin_time < 2.5 * period:
|
||||
while rclpy.ok(context=context) and time.time() - begin_time < 2.5 * period:
|
||||
executor.spin_once(timeout_sec=period / 10)
|
||||
|
||||
assert len(callbacks) == 2, 'should have received 2 callbacks, received %d' % len(callbacks)
|
||||
|
@ -109,7 +112,7 @@ def func_cancel_reset_timer(args):
|
|||
assert timer.is_canceled()
|
||||
callbacks = []
|
||||
begin_time = time.time()
|
||||
while rclpy.ok() and time.time() - begin_time < 2.5 * period:
|
||||
while rclpy.ok(context=context) and time.time() - begin_time < 2.5 * period:
|
||||
executor.spin_once(timeout_sec=period / 10)
|
||||
|
||||
assert timer.is_canceled()
|
||||
|
@ -119,14 +122,14 @@ def func_cancel_reset_timer(args):
|
|||
timer.reset()
|
||||
assert not timer.is_canceled()
|
||||
begin_time = time.time()
|
||||
while rclpy.ok() and time.time() - begin_time < 2.5 * period:
|
||||
while rclpy.ok(context=context) and time.time() - begin_time < 2.5 * period:
|
||||
executor.spin_once(timeout_sec=period / 10)
|
||||
|
||||
assert not timer.is_canceled()
|
||||
assert len(callbacks) == 2, 'should have received 2 callbacks, received %d' % len(callbacks)
|
||||
node.destroy_timer(timer)
|
||||
executor.shutdown()
|
||||
rclpy.shutdown()
|
||||
rclpy.shutdown(context=context)
|
||||
|
||||
return True
|
||||
|
||||
|
|
|
@ -127,7 +127,9 @@ class TimerWaitable(Waitable):
|
|||
|
||||
self._clock = Clock(clock_type=ClockType.STEADY_TIME)
|
||||
period_nanoseconds = 10000
|
||||
self.timer = _rclpy.rclpy_create_timer(self._clock._clock_handle, period_nanoseconds)[0]
|
||||
self.timer = _rclpy.rclpy_create_timer(
|
||||
self._clock._clock_handle, node.context.handle, period_nanoseconds
|
||||
)[0]
|
||||
self.timer_index = None
|
||||
self.timer_is_ready = False
|
||||
|
||||
|
@ -169,7 +171,7 @@ class SubscriptionWaitable(Waitable):
|
|||
def __init__(self, node):
|
||||
super().__init__(ReentrantCallbackGroup())
|
||||
|
||||
self.guard_condition = _rclpy.rclpy_create_guard_condition()[0]
|
||||
self.guard_condition = _rclpy.rclpy_create_guard_condition(node.context.handle)[0]
|
||||
self.guard_condition_index = None
|
||||
self.guard_is_ready = False
|
||||
|
||||
|
@ -216,7 +218,7 @@ class GuardConditionWaitable(Waitable):
|
|||
def __init__(self, node):
|
||||
super().__init__(ReentrantCallbackGroup())
|
||||
|
||||
self.guard_condition = _rclpy.rclpy_create_guard_condition()[0]
|
||||
self.guard_condition = _rclpy.rclpy_create_guard_condition(node.context.handle)[0]
|
||||
self.guard_condition_index = None
|
||||
self.guard_is_ready = False
|
||||
|
||||
|
@ -257,16 +259,17 @@ class TestWaitable(unittest.TestCase):
|
|||
|
||||
@classmethod
|
||||
def setUpClass(cls):
|
||||
rclpy.init()
|
||||
cls.node = rclpy.create_node('TestWaitable', namespace='/rclpy/test')
|
||||
cls.executor = SingleThreadedExecutor()
|
||||
cls.context = rclpy.context.Context()
|
||||
rclpy.init(context=cls.context)
|
||||
cls.node = rclpy.create_node('TestWaitable', namespace='/rclpy/test', context=cls.context)
|
||||
cls.executor = SingleThreadedExecutor(context=cls.context)
|
||||
cls.executor.add_node(cls.node)
|
||||
|
||||
@classmethod
|
||||
def tearDownClass(cls):
|
||||
cls.executor.shutdown()
|
||||
cls.node.destroy_node()
|
||||
rclpy.shutdown()
|
||||
rclpy.shutdown(context=cls.context)
|
||||
|
||||
def start_spin_thread(self, waitable):
|
||||
waitable.future = Future(executor=self.executor)
|
||||
|
|
Loading…
Reference in New Issue