-
Notifications
You must be signed in to change notification settings - Fork 237
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
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -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() | ||
|
@@ -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()): | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. why call implementation instead of calling utilities.get_default_domain_id? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. It is because utilities.py has imported context.py. In order to avoid interdependence, have to call rclpy_implementation. |
||
""" | ||
Initialize ROS communications for a given context. | ||
|
||
|
@@ -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 | ||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -39,6 +39,12 @@ def get_default_context(*, shutting_down=False): | |
return g_default_context | ||
|
||
|
||
def get_default_domain_id(): | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. maybe we could add test in https://github.com/ros2/rclpy/blob/master/rclpy/test/test_utilities.py. There was a problem hiding this comment. Choose a reason for hiding this commentThe 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 | ||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -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> | ||
|
@@ -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; | ||
} | ||
|
@@ -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 = | ||
|
@@ -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) | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. i was expecting this would call https://github.com/ros2/rcl/blob/6f3c3fb10391edaacb2676e2345a754bef1b76f2/rcl/include/rcl/domain_id.h#L40-L42 to get default domain id from rcl. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. This function is called at Besides, this domain id (RCL_DEFAULT_DOMAIN_ID) will be set to init_options in rclpy_init() (_rclpy.c) So not directly call rcl_get_default_domain_id() here. There was a problem hiding this comment. Choose a reason for hiding this commentThe 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[] = { | ||
{ | ||
|
@@ -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 */ | ||
}; | ||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Can we add test with specific domain_id in https://github.com/ros2/rclpy/blob/master/rclpy/test/test_init_shutdown.py?
There was a problem hiding this comment.
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.