From 9a01e159574ade56395216eed8a49a8212d59e5f Mon Sep 17 00:00:00 2001 From: ilithebutterfly Date: Fri, 21 Jun 2024 17:48:12 +0200 Subject: [PATCH] Cleaned up rove_nav_params.yaml and remapped nav's cmd_vel to nav_vel --- src/rove_navigation/config/rove_nav_params.yaml | 3 --- src/rove_navigation/launch/navigation.launch.py | 16 ++++++++++------ 2 files changed, 10 insertions(+), 9 deletions(-) diff --git a/src/rove_navigation/config/rove_nav_params.yaml b/src/rove_navigation/config/rove_nav_params.yaml index c290fad..319d890 100644 --- a/src/rove_navigation/config/rove_nav_params.yaml +++ b/src/rove_navigation/config/rove_nav_params.yaml @@ -224,7 +224,6 @@ global_costmap: origin_z: 0.0 z_resolution: 0.05 z_voxels: 16 - max_obstacle_height: 2.0 unknown_threshold: 15 mark_threshold: 0 observation_sources: pointcloud @@ -268,7 +267,6 @@ local_costmap: height: 3 resolution: 0.05 robot_radius: 0.22 # radius set and used, so no footprint points - resolution: 0.05 plugins: ["obstacle_layer", "voxel_layer", "inflation_layer"] obstacle_layer: plugin: "nav2_costmap_2d::ObstacleLayer" @@ -310,7 +308,6 @@ local_costmap: origin_z: 0.0 z_resolution: 0.05 z_voxels: 16 - max_obstacle_height: 2.0 unknown_threshold: 15 mark_threshold: 0 observation_sources: pointcloud diff --git a/src/rove_navigation/launch/navigation.launch.py b/src/rove_navigation/launch/navigation.launch.py index 53857fd..fb96800 100644 --- a/src/rove_navigation/launch/navigation.launch.py +++ b/src/rove_navigation/launch/navigation.launch.py @@ -2,14 +2,13 @@ from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription -from launch.actions import IncludeLaunchDescription +from launch.actions import IncludeLaunchDescription, GroupAction from launch.launch_description_sources import PythonLaunchDescriptionSource from launch.substitutions import PathJoinSubstitution from launch_ros.substitutions import FindPackageShare - +from launch_ros.actions import SetRemap def generate_launch_description(): - pkg_rove_navigation = get_package_share_directory('rove_navigation') navigation_launch_path = PathJoinSubstitution( @@ -24,9 +23,14 @@ def generate_launch_description(): launch_arguments={ 'use_sim_time': 'true', 'params_file': nav2_config_path - }.items() + }.items(), ) - + return LaunchDescription([ - nav + GroupAction( + actions=[ + SetRemap(src='cmd_vel', dst='nav_vel'), + nav, + ] + ) ])