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

Add ability to configure domain ID #594

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
10 changes: 8 additions & 2 deletions rclpy/rclpy/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -52,14 +52,20 @@
from rclpy.utilities import ok # noqa: F401 forwarding to this module
from rclpy.utilities import shutdown as _shutdown
from rclpy.utilities import try_shutdown # noqa: F401
from rclpy.utilities import get_default_domain_id

# 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: Optional[List[str]] = None, context: Context = None) -> None:
def init(
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

OK. I will supplement test codes.

*,
args: Optional[List[str]] = None,
context: Context = None,
domain_id: int = get_default_domain_id()
) -> None:
"""
Initialize ROS communications for a given context.

Expand All @@ -68,7 +74,7 @@ def init(*, args: Optional[List[str]] = None, context: Context = None) -> None:
(see :func:`.get_default_context`).
"""
context = get_default_context() if context is None else context
return context.init(args)
return context.init(args, domain_id=domain_id)


# The global spin functions need an executor to do the work
Expand Down
12 changes: 10 additions & 2 deletions rclpy/rclpy/context.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
from typing import List
from typing import Optional
import weakref
from rclpy.impl.implementation_singleton import rclpy_implementation


g_logging_configure_lock = threading.Lock()
Expand Down Expand Up @@ -46,7 +47,11 @@ def __init__(self):
def handle(self):
return self._handle

def init(self, args: Optional[List[str]] = None, *, initialize_logging: bool = True):
def init(self,
args: Optional[List[str]] = None,
*,
initialize_logging: bool = True,
domain_id: int = rclpy_implementation.rclpy_get_default_domain_id()):
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

why call implementation instead of calling utilities.get_default_domain_id?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It is because utilities.py has imported context.py.
https://github.com/Barry-Xu-2018/rclpy/blob/02d0bb6aa33b8e44a97ecac6cae4bbb8fce20f34/rclpy/rclpy/utilities.py#L22

In order to avoid interdependence, have to call rclpy_implementation.

"""
Initialize ROS communications for a given context.

Expand All @@ -56,7 +61,10 @@ def init(self, args: Optional[List[str]] = None, *, initialize_logging: bool = T
from rclpy.impl.implementation_singleton import rclpy_implementation
global g_logging_ref_count
with self._handle as capsule, self._lock:
rclpy_implementation.rclpy_init(args if args is not None else sys.argv, capsule)
rclpy_implementation.rclpy_init(
args if args is not None else sys.argv,
capsule,
domain_id)
if initialize_logging and not self._logging_initialized:
with g_logging_configure_lock:
g_logging_ref_count += 1
Expand Down
6 changes: 6 additions & 0 deletions rclpy/rclpy/utilities.py
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,12 @@ def get_default_context(*, shutting_down=False):
return g_default_context


def get_default_domain_id():
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

OK. I will supplement test codes.

"""Return default domain id from rcl."""
from rclpy.impl.implementation_singleton import rclpy_implementation
return rclpy_implementation.rclpy_get_default_domain_id()


def remove_ros_args(args=None):
# imported locally to avoid loading extensions on module import
from rclpy.impl.implementation_singleton import rclpy_implementation
Expand Down
37 changes: 36 additions & 1 deletion rclpy/src/rclpy/_rclpy.c
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
#include <rcl/remap.h>
#include <rcl/time.h>
#include <rcl/validate_topic_name.h>
#include <rcl/init_options.h>
#include <rcl_interfaces/msg/parameter_type.h>
#include <rcl_yaml_param_parser/parser.h>
#include <rcutils/allocator.h>
Expand Down Expand Up @@ -532,7 +533,9 @@ rclpy_init(PyObject * Py_UNUSED(self), PyObject * args)
PyObject * pyargs;
PyObject * pyseqlist;
PyObject * pycontext;
if (!PyArg_ParseTuple(args, "OO", &pyargs, &pycontext)) {
PY_LONG_LONG domain_id;

if (!PyArg_ParseTuple(args, "OOK", &pyargs, &pycontext, &domain_id)) {
// Exception raised
return NULL;
}
Expand Down Expand Up @@ -587,6 +590,15 @@ rclpy_init(PyObject * Py_UNUSED(self), PyObject * args)
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) {
// Set domain id
ret = rcl_init_options_set_domain_id(&init_options, (size_t)domain_id);
if (RCL_RET_OK != ret) {
PyErr_Format(
PyExc_RuntimeError,
"Failed to set domain id to init_options: %s",
rcl_get_error_string().str);
rcl_reset_error();
}
ret = rcl_init(num_args, arg_values, &init_options, context);
if (RCL_RET_OK == ret) {
int unparsed_ros_args_count =
Expand Down Expand Up @@ -5494,6 +5506,24 @@ rclpy_publisher_get_topic_name(PyObject * Py_UNUSED(self), PyObject * args)
return PyUnicode_FromString(topic_name);
}


/// Retrieves default domain id defined in rcl layer
/**
*
* \return the defined domain id
*/
static PyObject *
rclpy_get_default_domain_id(PyObject * Py_UNUSED(self), PyObject * args)
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This function is called at
https://github.com/Barry-Xu-2018/rclpy/blob/02d0bb6aa33b8e44a97ecac6cae4bbb8fce20f34/rclpy/rclpy/__init__.py#L63-L68.
rcl_get_default_domain_id() may return error.
rclpy_get_default_domain_id() directly return RCL_DEFAULT_DOMAIN_ID defined in rcl layer.

Besides, this domain id (RCL_DEFAULT_DOMAIN_ID) will be set to init_options in rclpy_init() (_rclpy.c)
In rcl_init(), if domain id equal to RCL_DEFAULT_DOMAIN_ID, rcl_get_default_domain_id() will be called.
Refer to https://github.com/ros2/rcl/blob/6f3c3fb10391edaacb2676e2345a754bef1b76f2/rcl/src/rcl/init.c#L146-L154.

So not directly call rcl_get_default_domain_id() here.

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

that makes sense.

{
(void)args;
#if __WORDSIZE == 64
return PyLong_FromUnsignedLongLong(RCL_DEFAULT_DOMAIN_ID);
#else
return PyLong_FromUnsignedLong(RCL_DEFAULT_DOMAIN_ID);
#endif
}


/// Define the public methods of this module
static PyMethodDef rclpy_methods[] = {
{
Expand Down Expand Up @@ -5909,6 +5939,11 @@ static PyMethodDef rclpy_methods[] = {
METH_VARARGS,
"Get the resolved name(topic) of publisher"
},
{
"rclpy_get_default_domain_id", rclpy_get_default_domain_id,
METH_NOARGS,
"Retrieve default domain ID"
},

{NULL, NULL, 0, NULL} /* sentinel */
};
Expand Down