diff --git a/launch/robot_navigation.launch.py b/launch/robot_navigation.launch.py index 7f9bf49..c6fd25b 100644 --- a/launch/robot_navigation.launch.py +++ b/launch/robot_navigation.launch.py @@ -28,7 +28,7 @@ from nav2_common.launch import RewrittenYaml def generate_launch_description(): # Get the launch directory - bringup_dir = get_package_share_directory('cps_rmp220_support') + bringup_dir = get_package_share_directory('nav2_bringup') namespace = LaunchConfiguration('namespace') use_sim_time = LaunchConfiguration('use_sim_time') @@ -83,7 +83,7 @@ def generate_launch_description(): declare_params_file_cmd = DeclareLaunchArgument( 'params_file', - default_value=os.path.join(bringup_dir, 'config', 'nav2_params.yaml'), + default_value=os.path.join(bringup_dir, 'params', 'nav2_params.yaml'), description='Full path to the ROS2 parameters file to use for all launched nodes') declare_autostart_cmd = DeclareLaunchArgument( @@ -178,7 +178,7 @@ def generate_launch_description(): parameters=[configured_params], arguments=['--ros-args', '--log-level', log_level], remappings=remappings + - [('cmd_vel', 'cmd_vel_nav'), ('cmd_vel_smoothed', 'cmd_vel_out')]), # so we get cmd_vel_smoothed as output to robot controller + [('cmd_vel', 'cmd_vel_nav'), ('cmd_vel_smoothed', 'cmd_vel')]), Node( package='nav2_lifecycle_manager', executable='lifecycle_manager',