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
15 changes: 15 additions & 0 deletions ros2cli/ros2cli/node/__init__.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
# Copyright 2018 Amazon.com, Inc. or its affiliates. All Rights Reserved.
#
# 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.node import HIDDEN_NODE_PREFIX
NODE_NAME_PREFIX = HIDDEN_NODE_PREFIX + 'ros2cli'
6 changes: 2 additions & 4 deletions ros2cli/ros2cli/node/direct.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,9 +16,7 @@

import rclpy

# TODO(mikaelarguedas) revisit this once it's specified
HIDDEN_NODE_PREFIX = '_'

from ros2cli.node import NODE_NAME_PREFIX
DEFAULT_TIMEOUT = 0.5


Expand All @@ -35,7 +33,7 @@ def timer_callback():

node_name_suffix = getattr(
args, 'node_name_suffix', '_%d' % os.getpid())
self.node = rclpy.create_node(HIDDEN_NODE_PREFIX + 'ros2cli_node' + node_name_suffix)
self.node = rclpy.create_node(NODE_NAME_PREFIX + node_name_suffix)
timeout = getattr(args, 'spin_time', DEFAULT_TIMEOUT)
timer = self.node.create_timer(timeout, timer_callback)

Expand Down
4 changes: 1 addition & 3 deletions ros2node/ros2node/api/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,9 @@

from collections import namedtuple

from rclpy.node import HIDDEN_NODE_PREFIX
from ros2cli.node.strategy import NodeStrategy

# TODO(mikaelarguedas) revisit this once it's specified
HIDDEN_NODE_PREFIX = '_'

NodeName = namedtuple('NodeName', ('name', 'namespace', 'full_name'))
TopicInfo = namedtuple('Topic', ('name', 'types'))

Expand Down
3 changes: 2 additions & 1 deletion ros2service/ros2service/verb/call.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
import time

import rclpy
from ros2cli.node import NODE_NAME_PREFIX
from ros2service.api import ServiceNameCompleter
from ros2service.api import ServiceTypeCompleter
from ros2service.verb import VerbExtension
Expand Down Expand Up @@ -76,7 +77,7 @@ def requester(service_type, service_name, values, period):

rclpy.init()

node = rclpy.create_node('requester_%s_%s' % (package_name, srv_name))
node = rclpy.create_node(NODE_NAME_PREFIX + '_requester_%s_%s' % (package_name, srv_name))

cli = node.create_client(srv_module, service_name)

Expand Down
3 changes: 2 additions & 1 deletion ros2topic/ros2topic/verb/pub.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
import time

import rclpy
from ros2cli.node import NODE_NAME_PREFIX
from ros2topic.api import import_message_type
from ros2topic.api import set_msg_fields
from ros2topic.api import SetFieldError
Expand Down Expand Up @@ -77,7 +78,7 @@ def publisher(
if not isinstance(values_dictionary, dict):
return 'The passed value needs to be a dictionary in YAML format'
if not node_name:
node_name = 'publisher_%s' % (message_type.replace('/', '_'),)
node_name = NODE_NAME_PREFIX + '_publisher_%s' % (message_type.replace('/', '_'), )
rclpy.init()

node = rclpy.create_node(node_name)
Expand Down