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
1 change: 1 addition & 0 deletions rclpy/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
<test_depend>ament_cmake_nose</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>rcl_interfaces</test_depend>
<test_depend>rosidl_generator_py</test_depend>
<test_depend>std_msgs</test_depend>

Expand Down
19 changes: 17 additions & 2 deletions rclpy/rclpy/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,15 +17,30 @@
from rclpy.constants import S_TO_NS
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
from rclpy.node import Node
from rclpy.validate_namespace import validate_namespace
from rclpy.validate_node_name import validate_node_name


def init(*, args=None):
# Now we can use _rclpy to call the implementation specific rclpy_init().
return _rclpy.rclpy_init(args if args is not None else sys.argv)


def create_node(node_name, *, namespace=None):
node_handle = _rclpy.rclpy_create_node(node_name, namespace or '')
namespace = namespace or ''
failed = False
try:
node_handle = _rclpy.rclpy_create_node(node_name, namespace)
except ValueError:
failed = True
if failed:
# these will raise more specific errors if the name or namespace is bad
validate_node_name(node_name)
# emulate what rcl_node_init() does to accept '' and relative namespaces
if not namespace:
namespace = '/'
if not namespace.startswith('/'):
namespace = '/' + namespace
validate_namespace(namespace)
return Node(node_handle)


Expand Down
47 changes: 40 additions & 7 deletions rclpy/rclpy/exceptions.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,15 +20,48 @@ def __init__(self, *args):
Exception.__init__(self, 'rclpy.init() has not been called', *args)


class NoImplementationAvailableException(Exception):
"""Raised when there is no rmw implementation with a Python extension available."""

def __init__(self, *args):
Exception.__init__(self, 'no rmw implementation with a Python extension available')


class NoTypeSupportImportedException(Exception):
"""Raised when there is no type support imported."""

def __init__(self, *args):
Exception.__init__(self, 'no type_support imported')


class NameValidationException(Exception):
"""Raised when a topic name, node name, or namespace are invalid."""

def __init__(self, name_type, name, error_msg, invalid_index, *args):
msg = """\
Invalid {name_type}: {error_msg}:
'{name}'
{indent}^\
""".format(name_type=name_type, name=name, error_msg=error_msg, indent=' ' * invalid_index)
Exception.__init__(self, msg)


class InvalidNamespaceException(NameValidationException):
"""Raised when a namespace is invalid."""

def __init__(self, name, error_msg, invalid_index, *args):
NameValidationException.__init__(self, "namespace", name, error_msg, invalid_index)


class InvalidNodeNameException(NameValidationException):
"""Raised when a node name is invalid."""

def __init__(self, name, error_msg, invalid_index, *args):
NameValidationException.__init__(self, "node name", name, error_msg, invalid_index)


class InvalidTopicNameException(NameValidationException):
"""Raised when a topic name is invalid."""

def __init__(self, name, error_msg, invalid_index, *args):
NameValidationException.__init__(self, "topic name", name, error_msg, invalid_index)


class InvalidServiceNameException(NameValidationException):
"""Raised when a service name is invalid."""

def __init__(self, name, error_msg, invalid_index, *args):
NameValidationException.__init__(self, "service name", name, error_msg, invalid_index)
33 changes: 33 additions & 0 deletions rclpy/rclpy/expand_topic_name.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
# Copyright 2017 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.

from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy


def expand_topic_name(topic_name, node_name, node_namespace):
"""
Expand a given topic name using given node name and namespace as well.

Note that this function can succeed but the expanded topic name may still
be invalid.
The :py:func:validate_full_topic_name(): should be used on the expanded
topic name to ensure it is valid after expansion.

:param topic_name str: topic name to be expanded
:param node_name str: name of the node that this topic is associated with
:param namespace str: namespace that the topic is within
:returns: expanded topic name which is fully qualified
:raises: ValueError if the topic name, node name or namespace are invalid
"""
return _rclpy.rclpy_expand_topic_name(topic_name, node_name, node_namespace)
69 changes: 55 additions & 14 deletions rclpy/rclpy/node.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,12 +15,17 @@
from rclpy.client import Client
from rclpy.constants import S_TO_NS
from rclpy.exceptions import NoTypeSupportImportedException
from rclpy.expand_topic_name import expand_topic_name
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
from rclpy.publisher import Publisher
from rclpy.qos import qos_profile_default, qos_profile_services_default
from rclpy.service import Service
from rclpy.subscription import Subscription
from rclpy.timer import WallTimer
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
from rclpy.validate_topic_name import validate_topic_name


class Node:
Expand All @@ -44,14 +49,32 @@ def handle(self, value):
def get_name(self):
return _rclpy.rclpy_get_node_name(self.handle)

def get_namespace(self):
return _rclpy.rclpy_get_node_namespace(self.handle)

def _validate_topic_or_service_name(self, topic_or_service_name, *, is_service=False):
name = self.get_name()
namespace = self.get_namespace()
validate_node_name(name)
validate_namespace(namespace)
validate_topic_name(topic_or_service_name, is_service=is_service)
expanded_topic_or_service_name = expand_topic_name(topic_or_service_name, name, namespace)
validate_full_topic_name(expanded_topic_or_service_name, is_service=is_service)

def create_publisher(self, msg_type, topic, *, qos_profile=qos_profile_default):
# this line imports the typesupport for the message module if not already done
if msg_type.__class__._TYPE_SUPPORT is None:
msg_type.__class__.__import_type_support__()
if msg_type.__class__._TYPE_SUPPORT is None:
raise NoTypeSupportImportedException
publisher_handle = _rclpy.rclpy_create_publisher(
self.handle, msg_type, topic, qos_profile.get_c_qos_profile())
failed = False
try:
publisher_handle = _rclpy.rclpy_create_publisher(
self.handle, msg_type, topic, qos_profile.get_c_qos_profile())
except ValueError:
failed = True
if failed:
self._validate_topic_or_service_name(topic)
publisher = Publisher(publisher_handle, msg_type, topic, qos_profile, self.handle)
self.publishers.append(publisher)
return publisher
Expand All @@ -62,8 +85,14 @@ def create_subscription(self, msg_type, topic, callback, *, qos_profile=qos_prof
msg_type.__class__.__import_type_support__()
if msg_type.__class__._TYPE_SUPPORT is None:
raise NoTypeSupportImportedException
[subscription_handle, subscription_pointer] = _rclpy.rclpy_create_subscription(
self.handle, msg_type, topic, qos_profile.get_c_qos_profile())
failed = False
try:
[subscription_handle, subscription_pointer] = _rclpy.rclpy_create_subscription(
self.handle, msg_type, topic, qos_profile.get_c_qos_profile())
except ValueError:
failed = True
if failed:
self._validate_topic_or_service_name(topic)

subscription = Subscription(
subscription_handle, subscription_pointer, msg_type,
Expand All @@ -76,11 +105,17 @@ def create_client(self, srv_type, srv_name, *, qos_profile=qos_profile_services_
srv_type.__class__.__import_type_support__()
if srv_type.__class__._TYPE_SUPPORT is None:
raise NoTypeSupportImportedException
[client_handle, client_pointer] = _rclpy.rclpy_create_client(
self.handle,
srv_type,
srv_name,
qos_profile.get_c_qos_profile())
failed = False
try:
[client_handle, client_pointer] = _rclpy.rclpy_create_client(
self.handle,
srv_type,
srv_name,
qos_profile.get_c_qos_profile())
except ValueError:
failed = True
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.clients.append(client)
Expand All @@ -92,11 +127,17 @@ def create_service(
srv_type.__class__.__import_type_support__()
if srv_type.__class__._TYPE_SUPPORT is None:
raise NoTypeSupportImportedException
[service_handle, service_pointer] = _rclpy.rclpy_create_service(
self.handle,
srv_type,
srv_name,
qos_profile.get_c_qos_profile())
failed = False
try:
[service_handle, service_pointer] = _rclpy.rclpy_create_service(
self.handle,
srv_type,
srv_name,
qos_profile.get_c_qos_profile())
except ValueError:
failed = True
if failed:
self._validate_topic_or_service_name(srv_name, is_service=True)
service = Service(
self.handle, service_handle, service_pointer,
srv_type, srv_name, callback, qos_profile)
Expand Down
41 changes: 41 additions & 0 deletions rclpy/rclpy/validate_full_topic_name.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
# Copyright 2017 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.

from rclpy.exceptions import InvalidServiceNameException
from rclpy.exceptions import InvalidTopicNameException
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy


def validate_full_topic_name(name, *, is_service=False):
"""
Validate a given topic or service name, and raise an exception if invalid.

The name must be fully-qualified and already expanded.

If the name is invalid then rclpy.exceptions.InvalidTopicNameException
will be raised.

:param name str: topic or service name to be validated
:param is_service bool: if true, InvalidServiceNameException is raised
:returns: True when it is valid
:raises: InvalidTopicNameException: when the name is invalid
"""
result = _rclpy.rclpy_get_validation_error_for_full_topic_name(name)
if result is None:
return True
error_msg, invalid_index = result
if is_service:
raise InvalidServiceNameException(name, error_msg, invalid_index)
else:
raise InvalidTopicNameException(name, error_msg, invalid_index)
38 changes: 38 additions & 0 deletions rclpy/rclpy/validate_namespace.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
# Copyright 2017 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.

from rclpy.exceptions import InvalidNamespaceException
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy


def validate_namespace(namespace):
"""
Validate a given namespace, and raise an exception if it is invalid.

Unlike the node constructor, which allows namespaces without a leading '/'
and empty namespaces "", this function requires that the namespace be
absolute and non-empty.

If the namespace is invalid then rclpy.exceptions.InvalidNamespaceException
will be raised.

:param namespace str: namespace to be validated
:returns: True when it is valid
:raises: InvalidNamespaceException: when the namespace is invalid
"""
result = _rclpy.rclpy_get_validation_error_for_namespace(namespace)
if result is None:
return True
error_msg, invalid_index = result
raise InvalidNamespaceException(namespace, error_msg, invalid_index)
34 changes: 34 additions & 0 deletions rclpy/rclpy/validate_node_name.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
# Copyright 2017 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.

from rclpy.exceptions import InvalidNodeNameException
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy


def validate_node_name(node_name):
"""
Validate a given node_name, and raise an exception if it is invalid.

If the node_name is invalid then rclpy.exceptions.InvalidNodeNameException
will be raised.

:param node_name str: node_name to be validated
:returns: True when it is valid
:raises: InvalidNodeNameException: when the node_name is invalid
"""
result = _rclpy.rclpy_get_validation_error_for_node_name(node_name)
if result is None:
return True
error_msg, invalid_index = result
raise InvalidNodeNameException(node_name, error_msg, invalid_index)
Loading