Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Replace deprecated launch params #1778

Merged
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
12 changes: 6 additions & 6 deletions nav2_bringup/bringup/launch/localization_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -82,24 +82,24 @@ def generate_launch_description():

Node(
package='nav2_map_server',
node_executable='map_server',
node_name='map_server',
executable='map_server',
name='map_server',
output='screen',
parameters=[configured_params],
remappings=remappings),

Node(
package='nav2_amcl',
node_executable='amcl',
node_name='amcl',
executable='amcl',
name='amcl',
output='screen',
parameters=[configured_params],
remappings=remappings),

Node(
package='nav2_lifecycle_manager',
node_executable='lifecycle_manager',
node_name='lifecycle_manager_localization',
executable='lifecycle_manager',
name='lifecycle_manager_localization',
output='screen',
parameters=[{'use_sim_time': use_sim_time},
{'autostart': autostart},
Expand Down
22 changes: 11 additions & 11 deletions nav2_bringup/bringup/launch/navigation_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -96,47 +96,47 @@ def generate_launch_description():

Node(
package='nav2_controller',
node_executable='controller_server',
executable='controller_server',
output='screen',
parameters=[configured_params],
remappings=remappings),

Node(
package='nav2_planner',
node_executable='planner_server',
node_name='planner_server',
executable='planner_server',
name='planner_server',
output='screen',
parameters=[configured_params],
remappings=remappings),

Node(
package='nav2_recoveries',
node_executable='recoveries_server',
node_name='recoveries_server',
executable='recoveries_server',
name='recoveries_server',
output='screen',
parameters=[configured_params],
remappings=remappings),

Node(
package='nav2_bt_navigator',
node_executable='bt_navigator',
node_name='bt_navigator',
executable='bt_navigator',
name='bt_navigator',
output='screen',
parameters=[configured_params],
remappings=remappings),

Node(
package='nav2_waypoint_follower',
node_executable='waypoint_follower',
node_name='waypoint_follower',
executable='waypoint_follower',
name='waypoint_follower',
output='screen',
parameters=[configured_params],
remappings=remappings),

Node(
package='nav2_lifecycle_manager',
node_executable='lifecycle_manager',
node_name='lifecycle_manager_navigation',
executable='lifecycle_manager',
name='lifecycle_manager_navigation',
output='screen',
parameters=[{'use_sim_time': use_sim_time},
{'autostart': autostart},
Expand Down
10 changes: 5 additions & 5 deletions nav2_bringup/bringup/launch/rviz_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -56,8 +56,8 @@ def generate_launch_description():
start_rviz_cmd = Node(
condition=UnlessCondition(use_namespace),
package='rviz2',
node_executable='rviz2',
node_name='rviz2',
executable='rviz2',
name='rviz2',
arguments=['-d', rviz_config_file],
output='screen')

Expand All @@ -68,9 +68,9 @@ def generate_launch_description():
start_namespaced_rviz_cmd = Node(
condition=IfCondition(use_namespace),
package='rviz2',
node_executable='rviz2',
node_name='rviz2',
node_namespace=namespace,
executable='rviz2',
name='rviz2',
namespace=namespace,
arguments=['-d', namespaced_rviz_config_file],
output='screen',
remappings=[('/tf', 'tf'),
Expand Down
2 changes: 1 addition & 1 deletion nav2_bringup/bringup/launch/spawn_tb3_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ def generate_launch_description():
# TODO(orduno) might not be necessary to have it's own package
launch_ros.actions.Node(
package='nav2_gazebo_spawner',
node_executable='nav2_gazebo_spawner',
executable='nav2_gazebo_spawner',
output='screen',
arguments=[
'--robot_name', launch.substitutions.LaunchConfiguration('robot_name'),
Expand Down
6 changes: 3 additions & 3 deletions nav2_bringup/bringup/launch/tb3_simulation_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -144,9 +144,9 @@ def generate_launch_description():
start_robot_state_publisher_cmd = Node(
condition=IfCondition(use_robot_state_pub),
package='robot_state_publisher',
node_executable='robot_state_publisher',
node_name='robot_state_publisher',
node_namespace=namespace,
executable='robot_state_publisher',
name='robot_state_publisher',
namespace=namespace,
output='screen',
parameters=[{'use_sim_time': use_sim_time}],
remappings=remappings,
Expand Down
4 changes: 2 additions & 2 deletions nav2_costmap_2d/test/integration/costmap_tests_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,8 @@ def main(argv=sys.argv[1:]):

lifecycle_manager = launch_ros.actions.Node(
package='nav2_lifecycle_manager',
node_executable='lifecycle_manager',
node_name='lifecycle_manager',
executable='lifecycle_manager',
name='lifecycle_manager',
output='screen',
parameters=[{'node_names': ['map_server']}, {'autostart': True}])

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,8 +25,8 @@ def generate_launch_description():
return LaunchDescription([
launch_ros.actions.Node(
package='nav2_map_server',
node_executable='map_server',
node_name='map_server',
executable='map_server',
name='map_server',
output='screen',
parameters=[{'yaml_filename': mapFile}])
])
6 changes: 3 additions & 3 deletions nav2_map_server/launch/map_saver_server.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ def generate_launch_description():
# Nodes launching commands
start_map_saver_server_cmd = launch_ros.actions.Node(
package='nav2_map_server',
node_executable='map_saver_server',
executable='map_saver_server',
output='screen',
emulate_tty=True, # https://github.com/ros2/launch/issues/188
parameters=[{'save_map_timeout': save_map_timeout},
Expand All @@ -39,8 +39,8 @@ def generate_launch_description():

start_lifecycle_manager_cmd = launch_ros.actions.Node(
package='nav2_lifecycle_manager',
node_executable='lifecycle_manager',
node_name='lifecycle_manager',
executable='lifecycle_manager',
name='lifecycle_manager',
output='screen',
emulate_tty=True, # https://github.com/ros2/launch/issues/188
parameters=[{'use_sim_time': use_sim_time},
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ def generate_launch_description():

map_saver_server_cmd = launch_ros.actions.Node(
package='nav2_map_server',
node_executable='map_saver_server',
executable='map_saver_server',
output='screen',
parameters=[os.path.join(os.getenv('TEST_DIR'),
'map_saver_params.yaml')])
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ def generate_launch_description():
return LaunchDescription([
launch_ros.actions.Node(
package='nav2_map_server',
node_executable='map_server',
executable='map_server',
output='screen',
parameters=[os.path.join(os.getenv('TEST_DIR'),
'map_server_params.yaml')])
Expand Down
14 changes: 7 additions & 7 deletions nav2_system_tests/src/localization/test_localization_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -35,28 +35,28 @@ def main(argv=sys.argv[1:]):
output='screen')
link_footprint = launch_ros.actions.Node(
package='tf2_ros',
node_executable='static_transform_publisher',
executable='static_transform_publisher',
output='screen',
arguments=['0', '0', '0', '0', '0', '0', 'base_footprint', 'base_link'])
footprint_scan = launch_ros.actions.Node(
package='tf2_ros',
node_executable='static_transform_publisher',
executable='static_transform_publisher',
output='screen',
arguments=['0', '0', '0', '0', '0', '0', 'base_link', 'base_scan'])
run_map_server = launch_ros.actions.Node(
package='nav2_map_server',
node_executable='map_server',
node_name='map_server',
executable='map_server',
name='map_server',
output='screen',
parameters=[{'yaml_filename': mapFile}])
run_amcl = launch_ros.actions.Node(
package='nav2_amcl',
node_executable='amcl',
executable='amcl',
output='screen')
run_lifecycle_manager = launch_ros.actions.Node(
package='nav2_lifecycle_manager',
node_executable='lifecycle_manager',
node_name='lifecycle_manager',
executable='lifecycle_manager',
name='lifecycle_manager',
output='screen',
parameters=[{'node_names': ['map_server', 'amcl']}, {'autostart': True}])
ld = LaunchDescription([launch_gazebo, link_footprint, footprint_scan,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,13 +59,13 @@ def generate_launch_description():
# using a local copy of TB3 urdf file
Node(
package='tf2_ros',
node_executable='static_transform_publisher',
executable='static_transform_publisher',
output='screen',
arguments=['0', '0', '0', '0', '0', '0', 'base_footprint', 'base_link']),

Node(
package='tf2_ros',
node_executable='static_transform_publisher',
executable='static_transform_publisher',
output='screen',
arguments=['0', '0', '0', '0', '0', '0', 'base_link', 'base_scan']),

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,13 +59,13 @@ def generate_launch_description():
# using a local copy of TB3 urdf file
Node(
package='tf2_ros',
node_executable='static_transform_publisher',
executable='static_transform_publisher',
output='screen',
arguments=['0', '0', '0', '0', '0', '0', 'base_footprint', 'base_link']),

Node(
package='tf2_ros',
node_executable='static_transform_publisher',
executable='static_transform_publisher',
output='screen',
arguments=['0', '0', '0', '0', '0', '0', 'base_link', 'base_scan']),

Expand Down
6 changes: 3 additions & 3 deletions nav2_system_tests/src/system/test_multi_robot_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ def generate_launch_description():
spawn_robots_cmds.append(
Node(
package='nav2_gazebo_spawner',
node_executable='nav2_gazebo_spawner',
executable='nav2_gazebo_spawner',
output='screen',
arguments=[
'--robot_name', TextSubstitution(text=robot['name']),
Expand All @@ -79,8 +79,8 @@ def generate_launch_description():
robot_state_pubs_cmds.append(
Node(
package='robot_state_publisher',
node_executable='robot_state_publisher',
node_namespace=TextSubstitution(text=robot['name']),
executable='robot_state_publisher',
namespace=TextSubstitution(text=robot['name']),
output='screen',
parameters=[{'use_sim_time': 'True'}],
remappings=[('/tf', 'tf'), ('/tf_static', 'tf_static')],
Expand Down
4 changes: 2 additions & 2 deletions nav2_system_tests/src/system/test_system_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -61,13 +61,13 @@ def generate_launch_description():
# using a local copy of TB3 urdf file
Node(
package='tf2_ros',
node_executable='static_transform_publisher',
executable='static_transform_publisher',
output='screen',
arguments=['0', '0', '0', '0', '0', '0', 'base_footprint', 'base_link']),

Node(
package='tf2_ros',
node_executable='static_transform_publisher',
executable='static_transform_publisher',
output='screen',
arguments=['0', '0', '0', '0', '0', '0', 'base_link', 'base_scan']),

Expand Down
10 changes: 5 additions & 5 deletions nav2_system_tests/src/system/tester_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ def __init__(
goal_pose: Pose,
namespace: str = ''
):
super().__init__(node_name='nav2_tester', namespace=namespace)
super().__init__(name='nav2_tester', namespace=namespace)
self.initial_pose_pub = self.create_publisher(PoseWithCovarianceStamped,
'initialpose', 10)
self.goal_pub = self.create_publisher(PoseStamped, 'goal_pose', 10)
Expand Down Expand Up @@ -148,17 +148,17 @@ def distanceFromGoal(self):
self.info_msg('Distance from goal is: ' + str(distance))
return distance

def wait_for_node_active(self, node_name: str):
def wait_for_node_active(self, name: str):
# Waits for the node within the tester namespace to become active
self.info_msg('Waiting for ' + node_name + ' to become active')
node_service = node_name + '/get_state'
self.info_msg('Waiting for ' + name + ' to become active')
node_service = name + '/get_state'
state_client = self.create_client(GetState, node_service)
while not state_client.wait_for_service(timeout_sec=1.0):
self.info_msg(node_service + ' service not available, waiting...')
req = GetState.Request() # empty request
state = 'UNKNOWN'
while (state != 'active'):
self.info_msg('Getting ' + node_name + ' state...')
self.info_msg('Getting ' + name + ' state...')
future = state_client.call_async(req)
rclpy.spin_until_future_complete(self, future)
if future.result() is not None:
Expand Down
8 changes: 4 additions & 4 deletions nav2_system_tests/src/updown/test_updown_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -34,25 +34,25 @@ def generate_launch_description():
# Specify the actions
start_tf_cmd_1 = Node(
package='tf2_ros',
node_executable='static_transform_publisher',
executable='static_transform_publisher',
output='screen',
arguments=['0', '0', '0', '0', '0', '0', 'map', 'odom'])

start_tf_cmd_2 = Node(
package='tf2_ros',
node_executable='static_transform_publisher',
executable='static_transform_publisher',
output='screen',
arguments=['0', '0', '0', '0', '0', '0', 'odom', 'base_footprint'])

start_tf_cmd_3 = Node(
package='tf2_ros',
node_executable='static_transform_publisher',
executable='static_transform_publisher',
output='screen',
arguments=['0', '0', '0', '0', '0', '0', 'base_footprint', 'base_link'])

start_tf_cmd_4 = Node(
package='tf2_ros',
node_executable='static_transform_publisher',
executable='static_transform_publisher',
output='screen',
arguments=['0', '0', '0', '0', '0', '0', 'base_link', 'base_scan'])

Expand Down
4 changes: 2 additions & 2 deletions nav2_system_tests/src/waypoint_follower/test_case_py.launch
Original file line number Diff line number Diff line change
Expand Up @@ -59,13 +59,13 @@ def generate_launch_description():
# using a local copy of TB3 urdf file
Node(
package='tf2_ros',
node_executable='static_transform_publisher',
executable='static_transform_publisher',
output='screen',
arguments=['0', '0', '0', '0', '0', '0', 'base_footprint', 'base_link']),

Node(
package='tf2_ros',
node_executable='static_transform_publisher',
executable='static_transform_publisher',
output='screen',
arguments=['0', '0', '0', '0', '0', '0', 'base_link', 'base_scan']),

Expand Down
2 changes: 1 addition & 1 deletion nav2_system_tests/src/waypoint_follower/tester.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@
class WaypointFollowerTest(Node):

def __init__(self):
super().__init__(node_name='nav2_waypoint_tester', namespace='')
super().__init__(name='nav2_waypoint_tester', namespace='')
self.waypoints = None
self.action_client = ActionClient(self, FollowWaypoints, 'FollowWaypoints')
self.initial_pose_pub = self.create_publisher(PoseWithCovarianceStamped,
Expand Down