Skip to content

Commit 13aea93

Browse files
Switch to new-style static_transform_publisher arguments. (ros-navigation#4563)
These arguments have been the preferred way to use things since at least Humble. This avoids warnings when running it for the tests. Signed-off-by: Chris Lalancette <[email protected]> Signed-off-by: Vladyslav Hrynchak <[email protected]>
1 parent 30dac64 commit 13aea93

File tree

9 files changed

+188
-26
lines changed

9 files changed

+188
-26
lines changed

nav2_costmap_2d/test/integration/costmap_tests_launch.py

Lines changed: 20 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -36,14 +36,32 @@ def main(argv=sys.argv[1:]):
3636
package='tf2_ros',
3737
executable='static_transform_publisher',
3838
output='screen',
39-
arguments=['0', '0', '0', '0', '0', '0', 'map', 'odom'],
39+
arguments=[
40+
'--x', '0',
41+
'--y', '0',
42+
'--z', '0',
43+
'--roll', '0',
44+
'--pitch', '0',
45+
'--yaw', '0',
46+
'--frame-id', 'map',
47+
'--child-frame-id', 'odom'
48+
],
4049
)
4150

4251
odom_to_base_link = launch_ros.actions.Node(
4352
package='tf2_ros',
4453
executable='static_transform_publisher',
4554
output='screen',
46-
arguments=['0', '0', '0', '0', '0', '0', 'odom', 'base_link'],
55+
arguments=[
56+
'--x', '0',
57+
'--y', '0',
58+
'--z', '0',
59+
'--roll', '0',
60+
'--pitch', '0',
61+
'--yaw', '0',
62+
'--frame-id', 'odom',
63+
'--child-frame-id', 'base_link'
64+
],
4765
)
4866

4967
lifecycle_manager = launch_ros.actions.Node(

nav2_system_tests/src/behaviors/backup/test_backup_behavior.launch.py

Lines changed: 10 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -94,7 +94,16 @@ def generate_launch_description():
9494
package='tf2_ros',
9595
executable='static_transform_publisher',
9696
output='screen',
97-
arguments=['0', '0', '0', '0', '0', '0', 'map', 'odom'],
97+
arguments=[
98+
'--x', '0',
99+
'--y', '0',
100+
'--z', '0',
101+
'--roll', '0',
102+
'--pitch', '0',
103+
'--yaw', '0',
104+
'--frame-id', 'map',
105+
'--child-frame-id', 'odom'
106+
],
98107
parameters=[{'use_sim_time': True}],
99108
),
100109
# Need transforms

nav2_system_tests/src/behaviors/drive_on_heading/test_drive_on_heading_behavior.launch.py

Lines changed: 10 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -94,7 +94,16 @@ def generate_launch_description():
9494
package='tf2_ros',
9595
executable='static_transform_publisher',
9696
output='screen',
97-
arguments=['0', '0', '0', '0', '0', '0', 'map', 'odom'],
97+
arguments=[
98+
'--x', '0',
99+
'--y', '0',
100+
'--z', '0',
101+
'--roll', '0',
102+
'--pitch', '0',
103+
'--yaw', '0',
104+
'--frame-id', 'map',
105+
'--child-frame-id', 'odom'
106+
],
98107
parameters=[{'use_sim_time': True}],
99108
),
100109
# Need transforms

nav2_system_tests/src/behaviors/spin/test_spin_behavior.launch.py

Lines changed: 10 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -94,7 +94,16 @@ def generate_launch_description():
9494
package='tf2_ros',
9595
executable='static_transform_publisher',
9696
output='screen',
97-
arguments=['0', '0', '0', '0', '0', '0', 'map', 'odom'],
97+
arguments=[
98+
'--x', '0',
99+
'--y', '0',
100+
'--z', '0',
101+
'--roll', '0',
102+
'--pitch', '0',
103+
'--yaw', '0',
104+
'--frame-id', 'map',
105+
'--child-frame-id', 'odom'
106+
],
98107
parameters=[{'use_sim_time': True}],
99108
),
100109
# Need transforms

nav2_system_tests/src/error_codes/test_error_codes_launch.py

Lines changed: 20 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -37,13 +37,31 @@ def generate_launch_description():
3737
package='tf2_ros',
3838
executable='static_transform_publisher',
3939
output='screen',
40-
arguments=['0', '0', '0', '0', '0', '0', 'map', 'odom'],
40+
arguments=[
41+
'--x', '0',
42+
'--y', '0',
43+
'--z', '0',
44+
'--roll', '0',
45+
'--pitch', '0',
46+
'--yaw', '0',
47+
'--frame-id', 'map',
48+
'--child-frame-id', 'odom'
49+
],
4150
),
4251
Node(
4352
package='tf2_ros',
4453
executable='static_transform_publisher',
4554
output='screen',
46-
arguments=['0', '0', '0', '0', '0', '0', 'odom', 'base_link'],
55+
arguments=[
56+
'--x', '0',
57+
'--y', '0',
58+
'--z', '0',
59+
'--roll', '0',
60+
'--pitch', '0',
61+
'--yaw', '0',
62+
'--frame-id', 'odom',
63+
'--child-frame-id', 'base_link'
64+
],
4765
),
4866
Node(
4967
package='nav2_controller',

nav2_system_tests/src/gps_navigation/test_case_py.launch.py

Lines changed: 38 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -64,34 +64,61 @@ def generate_launch_description():
6464
package='tf2_ros',
6565
executable='static_transform_publisher',
6666
output='screen',
67-
arguments=['0', '0', '0', '0', '0', '0', 'base_footprint', 'base_link'],
67+
arguments=[
68+
'--x', '0',
69+
'--y', '0',
70+
'--z', '0',
71+
'--roll', '0',
72+
'--pitch', '0',
73+
'--yaw', '0',
74+
'--frame-id', 'base_footprint',
75+
'--child-frame-id', 'base_link'
76+
],
6877
),
6978
Node(
7079
package='tf2_ros',
7180
executable='static_transform_publisher',
7281
output='screen',
73-
arguments=['0', '0', '0', '0', '0', '0', 'base_link', 'base_scan'],
82+
arguments=[
83+
'--x', '0',
84+
'--y', '0',
85+
'--z', '0',
86+
'--roll', '0',
87+
'--pitch', '0',
88+
'--yaw', '0',
89+
'--frame-id', 'base_link',
90+
'--child-frame-id', 'base_scan'
91+
],
7492
),
7593
Node(
7694
package='tf2_ros',
7795
executable='static_transform_publisher',
7896
output='screen',
7997
arguments=[
80-
'-0.32',
81-
'0',
82-
'0.068',
83-
'0',
84-
'0',
85-
'0',
86-
'base_link',
87-
'imu_link',
98+
'--x', '-0.32',
99+
'--y', '0',
100+
'--z', '0.068',
101+
'--roll', '0',
102+
'--pitch', '0',
103+
'--yaw', '0',
104+
'--frame-id', 'base_link',
105+
'--child-frame-id', 'imu_link'
88106
],
89107
),
90108
Node(
91109
package='tf2_ros',
92110
executable='static_transform_publisher',
93111
output='screen',
94-
arguments=['0', '0', '0', '0', '0', '0', 'base_link', 'gps_link'],
112+
arguments=[
113+
'--x', '0',
114+
'--y', '0',
115+
'--z', '0',
116+
'--roll', '0',
117+
'--pitch', '0',
118+
'--yaw', '0',
119+
'--frame-id', 'base_link',
120+
'--child-frame-id', 'gps_link'
121+
],
95122
),
96123
IncludeLaunchDescription(
97124
PythonLaunchDescriptionSource(

nav2_system_tests/src/updown/test_updown_launch.py

Lines changed: 40 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -34,28 +34,64 @@ def generate_launch_description():
3434
package='tf2_ros',
3535
executable='static_transform_publisher',
3636
output='screen',
37-
arguments=['0', '0', '0', '0', '0', '0', 'map', 'odom'],
37+
arguments=[
38+
'--x', '0',
39+
'--y', '0',
40+
'--z', '0',
41+
'--roll', '0',
42+
'--pitch', '0',
43+
'--yaw', '0',
44+
'--frame-id', 'map',
45+
'--child-frame-id', 'odom'
46+
],
3847
)
3948

4049
start_tf_cmd_2 = Node(
4150
package='tf2_ros',
4251
executable='static_transform_publisher',
4352
output='screen',
44-
arguments=['0', '0', '0', '0', '0', '0', 'odom', 'base_footprint'],
53+
arguments=[
54+
'--x', '0',
55+
'--y', '0',
56+
'--z', '0',
57+
'--roll', '0',
58+
'--pitch', '0',
59+
'--yaw', '0',
60+
'--frame-id', 'odom',
61+
'--child-frame-id', 'base_footprint'
62+
],
4563
)
4664

4765
start_tf_cmd_3 = Node(
4866
package='tf2_ros',
4967
executable='static_transform_publisher',
5068
output='screen',
51-
arguments=['0', '0', '0', '0', '0', '0', 'base_footprint', 'base_link'],
69+
arguments=[
70+
'--x', '0',
71+
'--y', '0',
72+
'--z', '0',
73+
'--roll', '0',
74+
'--pitch', '0',
75+
'--yaw', '0',
76+
'--frame-id', 'base_footprint',
77+
'--child-frame-id', 'base_link'
78+
],
5279
)
5380

5481
start_tf_cmd_4 = Node(
5582
package='tf2_ros',
5683
executable='static_transform_publisher',
5784
output='screen',
58-
arguments=['0', '0', '0', '0', '0', '0', 'base_link', 'base_scan'],
85+
arguments=[
86+
'--x', '0',
87+
'--y', '0',
88+
'--z', '0',
89+
'--roll', '0',
90+
'--pitch', '0',
91+
'--yaw', '0',
92+
'--frame-id', 'base_link',
93+
'--child-frame-id', 'base_scan'
94+
],
5995
)
6096

6197
nav2_bringup = launch.actions.IncludeLaunchDescription(

tools/planner_benchmarking/planning_benchmark_bringup.py

Lines changed: 20 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -53,13 +53,31 @@ def generate_launch_description():
5353
package='tf2_ros',
5454
executable='static_transform_publisher',
5555
output='screen',
56-
arguments=['0', '0', '0', '0', '0', '0', 'base_link', 'map'],
56+
arguments=[
57+
'--x', '0',
58+
'--y', '0',
59+
'--z', '0',
60+
'--roll', '0',
61+
'--pitch', '0',
62+
'--yaw', '0',
63+
'--frame-id', 'base_link',
64+
'--child-frame-id', 'map'
65+
],
5766
),
5867
Node(
5968
package='tf2_ros',
6069
executable='static_transform_publisher',
6170
output='screen',
62-
arguments=['0', '0', '0', '0', '0', '0', 'base_link', 'odom'],
71+
arguments=[
72+
'--x', '0',
73+
'--y', '0',
74+
'--z', '0',
75+
'--roll', '0',
76+
'--pitch', '0',
77+
'--yaw', '0',
78+
'--frame-id', 'base_link',
79+
'--child-frame-id', 'odom'
80+
],
6381
),
6482
Node(
6583
package='nav2_lifecycle_manager',

tools/smoother_benchmarking/smoother_benchmark_bringup.py

Lines changed: 20 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -35,14 +35,32 @@ def generate_launch_description():
3535
package='tf2_ros',
3636
executable='static_transform_publisher',
3737
output='screen',
38-
arguments=['0', '0', '0', '0', '0', '0', 'base_link', 'map'],
38+
arguments=[
39+
'--x', '0',
40+
'--y', '0',
41+
'--z', '0',
42+
'--roll', '0',
43+
'--pitch', '0',
44+
'--yaw', '0',
45+
'--frame-id', 'base_link',
46+
'--child-frame-id', 'map'
47+
],
3948
)
4049

4150
static_transform_two = Node(
4251
package='tf2_ros',
4352
executable='static_transform_publisher',
4453
output='screen',
45-
arguments=['0', '0', '0', '0', '0', '0', 'base_link', 'odom'],
54+
arguments=[
55+
'--x', '0',
56+
'--y', '0',
57+
'--z', '0',
58+
'--roll', '0',
59+
'--pitch', '0',
60+
'--yaw', '0',
61+
'--frame-id', 'base_link',
62+
'--child-frame-id', 'odom'
63+
],
4664
)
4765

4866
start_map_server_cmd = Node(

0 commit comments

Comments
 (0)