Skip to content

Commit 89f56e1

Browse files
authored
add option to support use_sim_time. (#581)
* add option to support use_sim_time. Signed-off-by: Tomoya.Fujita <[email protected]> * requirement is delay, not bandwidth. Signed-off-by: Tomoya.Fujita <[email protected]> * add test for DirectNode Class. Signed-off-by: Tomoya.Fujita <[email protected]>
1 parent 14eb345 commit 89f56e1

File tree

3 files changed

+75
-1
lines changed

3 files changed

+75
-1
lines changed

ros2cli/ros2cli/node/direct.py

Lines changed: 10 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
import rclpy
1818
import rclpy.action
1919

20+
from rclpy.parameter import Parameter
2021
from ros2cli.node import NODE_NAME_PREFIX
2122
DEFAULT_TIMEOUT = 0.5
2223

@@ -38,13 +39,18 @@ def timer_callback():
3839
args, 'node_name_suffix', '_%d' % os.getpid())
3940
start_parameter_services = getattr(
4041
args, 'start_parameter_services', False)
42+
use_sim_time = getattr(args, 'use_sim_time', False)
4143

4244
if node_name is None:
4345
node_name = NODE_NAME_PREFIX + node_name_suffix
4446

4547
self.node = rclpy.create_node(
4648
node_name,
47-
start_parameter_services=start_parameter_services)
49+
start_parameter_services=start_parameter_services,
50+
parameter_overrides=[
51+
Parameter('use_sim_time', value=use_sim_time)
52+
])
53+
4854
timeout = getattr(args, 'spin_time', DEFAULT_TIMEOUT)
4955
timer = self.node.create_timer(timeout, timer_callback)
5056

@@ -86,3 +92,6 @@ def add_arguments(parser):
8692
'--spin-time', type=float, default=DEFAULT_TIMEOUT,
8793
help='Spin time in seconds to wait for discovery (only applies when '
8894
'not using an already running daemon)')
95+
parser.add_argument(
96+
'-s', '--use-sim-time', action='store_true',
97+
help='Enable ROS simulation time')

ros2cli/test/test_direct.py

Lines changed: 63 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,63 @@
1+
# Copyright 2020 Sony Corporation.
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
import argparse
16+
17+
import pytest
18+
19+
from ros2cli.node.direct import add_arguments as add_direct_node_arguments
20+
from ros2cli.node.direct import DEFAULT_TIMEOUT
21+
from ros2cli.node.direct import DirectNode
22+
23+
TEST_NODE_NAME = 'test_node'
24+
25+
26+
@pytest.fixture(scope='function')
27+
def test_arguments_parser():
28+
parser = argparse.ArgumentParser()
29+
add_direct_node_arguments(parser)
30+
return parser
31+
32+
33+
def test_default_arguments(test_arguments_parser):
34+
args = test_arguments_parser.parse_args()
35+
assert not args.use_sim_time
36+
assert DEFAULT_TIMEOUT == args.spin_time
37+
38+
39+
def test_use_sim_time_arguments(test_arguments_parser):
40+
args = test_arguments_parser.parse_args(['--use-sim-time'])
41+
assert args.use_sim_time
42+
assert DEFAULT_TIMEOUT == args.spin_time
43+
44+
45+
def test_spin_time_arguments(test_arguments_parser):
46+
args = test_arguments_parser.parse_args(['--spin-time', '10.0'])
47+
assert not args.use_sim_time
48+
assert 10.0 == args.spin_time
49+
50+
51+
def test_use_sim_time_parameter():
52+
with DirectNode(args=[], node_name=TEST_NODE_NAME) as direct_node:
53+
assert not direct_node.node.get_parameter('use_sim_time').value
54+
55+
args = argparse.Namespace(use_sim_time=False)
56+
with DirectNode(args, node_name=TEST_NODE_NAME) as direct_node:
57+
assert not direct_node.node.get_parameter('use_sim_time').value
58+
59+
# TODO(fujitatomoya): enable this test once /clock callback thread is insulated.
60+
# see https://github.com/ros2/rclcpp/issues/1542
61+
# args = argparse.Namespace(use_sim_time=True)
62+
# with DirectNode(args, node_name=TEST_NODE_NAME) as direct_node:
63+
# assert direct_node.node.get_parameter('use_sim_time').value

ros2topic/ros2topic/verb/delay.py

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -40,6 +40,7 @@
4040

4141
from rclpy.qos import qos_profile_sensor_data
4242
from rclpy.time import Time
43+
from ros2cli.node.direct import add_arguments as add_direct_node_arguments
4344
from ros2cli.node.direct import DirectNode
4445
from ros2topic.api import get_msg_class
4546
from ros2topic.api import TopicNameCompleter
@@ -71,6 +72,7 @@ def add_arguments(self, parser, cli_name):
7172
'--window', '-w', type=positive_int, default=DEFAULT_WINDOW_SIZE,
7273
help='window size, in # of messages, for calculating rate, '
7374
'string to (default: %d)' % DEFAULT_WINDOW_SIZE)
75+
add_direct_node_arguments(parser)
7476

7577
def main(self, *, args):
7678
return main(args)

0 commit comments

Comments
 (0)