Skip to content

Conversation

@wjwwood
Copy link
Member

@wjwwood wjwwood commented May 25, 2017

Connects to ros2/rcl#137

Here are some examples of what it looks like when you give invalid names now:

  • invalid node name
% python3 -c "import rclpy; rclpy.init(); rclpy.create_node('invalid_node?')"
Traceback (most recent call last):
  File "<string>", line 1, in <module>
  File "/Users/william/ros2_ws/install/lib/python3.6/site-packages/rclpy/__init__.py", line 38, in create_node
    validate_node_name(node_name)
  File "/Users/william/ros2_ws/install/lib/python3.6/site-packages/rclpy/validate_node_name.py", line 34, in validate_node_name
    raise InvalidNodeNameException(node_name, error_msg, invalid_index)
rclpy.exceptions.InvalidNodeNameException: Invalid node name: node name must not contain characters other than alphanumerics or '_':
  'invalid_node?'
               ^
  • invalid node namespace
% python3 -c "
import rclpy
rclpy.init()
rclpy.create_node('node_name', namespace='/invalid_ns?')"
Traceback (most recent call last):
  File "<string>", line 4, in <module>
  File "/Users/william/ros2_ws/install/lib/python3.6/site-packages/rclpy/__init__.py", line 43, in create_node
    validate_namespace(namespace)
  File "/Users/william/ros2_ws/install/lib/python3.6/site-packages/rclpy/validate_namespace.py", line 38, in validate_namespace
    raise InvalidNamespaceException(namespace, error_msg, invalid_index)
rclpy.exceptions.InvalidNamespaceException: Invalid namespace: namespace must not contain characters other than alphanumerics, '_', or '/':
  '/invalid_ns?'
              ^
  • invalid topic name
% python3 -c "
import rclpy
from std_msgs.msg import String
rclpy.init()
n = rclpy.create_node('node_name')
n.create_publisher(String, 'chatter?')"
Traceback (most recent call last):
  File "<string>", line 6, in <module>
  File "/Users/william/ros2_ws/install/lib/python3.6/site-packages/rclpy/node.py", line 77, in create_publisher
    self._validate_topic_or_service_name(topic)
  File "/Users/william/ros2_ws/install/lib/python3.6/site-packages/rclpy/node.py", line 60, in _validate_topic_or_service_name
    validate_topic_name(topic_or_service_name, is_service=is_service)
  File "/Users/william/ros2_ws/install/lib/python3.6/site-packages/rclpy/validate_topic_name.py", line 41, in validate_topic_name
    raise InvalidTopicNameException(name, error_msg, invalid_index)
rclpy.exceptions.InvalidTopicNameException: Invalid topic name: topic name must not contain characters other than alphanumerics, '_', '~', '{', or '}':
  'chatter?'
          ^
  • invalid service name
% python3 -c "
import rclpy
from std_srvs.srv import Empty
rclpy.init()
n = rclpy.create_node('node_name')
n.create_client(Empty, 'empty?')"
Traceback (most recent call last):
  File "<string>", line 6, in <module>
  File "/Users/william/ros2_ws/install/lib/python3.6/site-packages/rclpy/node.py", line 118, in create_client
    self._validate_topic_or_service_name(srv_name, is_service=True)
  File "/Users/william/ros2_ws/install/lib/python3.6/site-packages/rclpy/node.py", line 60, in _validate_topic_or_service_name
    validate_topic_name(topic_or_service_name, is_service=is_service)
  File "/Users/william/ros2_ws/install/lib/python3.6/site-packages/rclpy/validate_topic_name.py", line 39, in validate_topic_name
    raise InvalidServiceNameException(name, error_msg, invalid_index)
rclpy.exceptions.InvalidServiceNameException: Invalid service name: topic name must not contain characters other than alphanumerics, '_', '~', '{', or '}':
  'empty?'
        ^

@wjwwood wjwwood added the in progress Actively being worked on (Kanban column) label May 25, 2017
@wjwwood wjwwood self-assigned this May 25, 2017
@wjwwood wjwwood mentioned this pull request May 25, 2017
@wjwwood wjwwood added in review Waiting for review (Kanban column) and removed in progress Actively being worked on (Kanban column) labels May 27, 2017
@wjwwood wjwwood merged commit 22bc843 into master May 31, 2017
@wjwwood wjwwood deleted the use_namespaces branch May 31, 2017 01:24
@wjwwood wjwwood removed the in review Waiting for review (Kanban column) label May 31, 2017
@dhood dhood mentioned this pull request Nov 16, 2017
ryantqiu pushed a commit to snorkel-marlin-repos/ros2_rclpy_pr_86_32c46bfb-f2ba-40d1-80ec-0cac3627833d that referenced this pull request Oct 1, 2025
Original PR #86 by wjwwood
Original: ros2/rclpy#86
ryantqiu added a commit to snorkel-marlin-repos/ros2_rclpy_pr_86_32c46bfb-f2ba-40d1-80ec-0cac3627833d that referenced this pull request Oct 1, 2025
Merged from original PR #86
Original: ros2/rclpy#86
ryantqiu pushed a commit to snorkel-marlin-repos/ros2_rclpy_pr_86_c650a02a-e7d0-4c01-b765-ecf9215654b3 that referenced this pull request Oct 2, 2025
Original PR #86 by wjwwood
Original: ros2/rclpy#86
ryantqiu added a commit to snorkel-marlin-repos/ros2_rclpy_pr_86_c650a02a-e7d0-4c01-b765-ecf9215654b3 that referenced this pull request Oct 2, 2025
Merged from original PR #86
Original: ros2/rclpy#86
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

3 participants