nav2 launch files added

This commit is contained in:
Rooholla-KhorramBakht 2024-05-01 10:43:02 +08:00
parent 97efd0d426
commit c1ab3cbfda
4 changed files with 687 additions and 82 deletions

View File

@ -0,0 +1,272 @@
# Copyright (c) 2018 Intel Corporation
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, GroupAction, SetEnvironmentVariable
from launch.conditions import IfCondition
from launch.substitutions import LaunchConfiguration, PythonExpression
from launch_ros.actions import LoadComposableNodes
from launch_ros.actions import Node
from launch_ros.descriptions import ComposableNode, ParameterFile
from nav2_common.launch import RewrittenYaml
def generate_launch_description():
# Get the launch directory
bringup_dir = get_package_share_directory('nav2_bringup')
namespace = LaunchConfiguration('namespace')
use_sim_time = LaunchConfiguration('use_sim_time')
autostart = LaunchConfiguration('autostart')
params_file = LaunchConfiguration('params_file')
use_composition = LaunchConfiguration('use_composition')
container_name = LaunchConfiguration('container_name')
container_name_full = (namespace, '/', container_name)
use_respawn = LaunchConfiguration('use_respawn')
log_level = LaunchConfiguration('log_level')
lifecycle_nodes = ['controller_server',
'smoother_server',
'planner_server',
'behavior_server',
'bt_navigator',
'waypoint_follower',
'velocity_smoother']
# Map fully qualified names to relative ones so the node's namespace can be prepended.
# In case of the transforms (tf), currently, there doesn't seem to be a better alternative
# https://github.com/ros/geometry2/issues/32
# https://github.com/ros/robot_state_publisher/pull/30
# TODO(orduno) Substitute with `PushNodeRemapping`
# https://github.com/ros2/launch_ros/issues/56
remappings = [('/tf', 'tf'),
('/tf_static', 'tf_static'),('/cmd_vel', '/nav2/cmd_vel')]
# Create our own temporary YAML files that include substitutions
param_substitutions = {
'use_sim_time': use_sim_time,
'autostart': autostart}
configured_params = ParameterFile(
RewrittenYaml(
source_file=params_file,
root_key=namespace,
param_rewrites=param_substitutions,
convert_types=True),
allow_substs=True)
stdout_linebuf_envvar = SetEnvironmentVariable(
'RCUTILS_LOGGING_BUFFERED_STREAM', '1')
declare_namespace_cmd = DeclareLaunchArgument(
'namespace',
default_value='',
description='Top-level namespace')
declare_use_sim_time_cmd = DeclareLaunchArgument(
'use_sim_time',
default_value='false',
description='Use simulation (Gazebo) clock if true')
declare_params_file_cmd = DeclareLaunchArgument(
'params_file',
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(
'autostart', default_value='true',
description='Automatically startup the nav2 stack')
declare_use_composition_cmd = DeclareLaunchArgument(
'use_composition', default_value='False',
description='Use composed bringup if True')
declare_container_name_cmd = DeclareLaunchArgument(
'container_name', default_value='nav2_container',
description='the name of conatiner that nodes will load in if use composition')
declare_use_respawn_cmd = DeclareLaunchArgument(
'use_respawn', default_value='False',
description='Whether to respawn if a node crashes. Applied when composition is disabled.')
declare_log_level_cmd = DeclareLaunchArgument(
'log_level', default_value='info',
description='log level')
load_nodes = GroupAction(
condition=IfCondition(PythonExpression(['not ', use_composition])),
actions=[
Node(
package='nav2_controller',
executable='controller_server',
output='screen',
respawn=use_respawn,
respawn_delay=2.0,
parameters=[configured_params],
arguments=['--ros-args', '--log-level', log_level],
remappings=remappings + [('cmd_vel', 'cmd_vel_nav')]),
Node(
package='nav2_smoother',
executable='smoother_server',
name='smoother_server',
output='screen',
respawn=use_respawn,
respawn_delay=2.0,
parameters=[configured_params],
arguments=['--ros-args', '--log-level', log_level],
remappings=remappings),
Node(
package='nav2_planner',
executable='planner_server',
name='planner_server',
output='screen',
respawn=use_respawn,
respawn_delay=2.0,
parameters=[configured_params],
arguments=['--ros-args', '--log-level', log_level],
remappings=remappings),
Node(
package='nav2_behaviors',
executable='behavior_server',
name='behavior_server',
output='screen',
respawn=use_respawn,
respawn_delay=2.0,
parameters=[configured_params],
arguments=['--ros-args', '--log-level', log_level],
remappings=remappings),
Node(
package='nav2_bt_navigator',
executable='bt_navigator',
name='bt_navigator',
output='screen',
respawn=use_respawn,
respawn_delay=2.0,
parameters=[configured_params],
arguments=['--ros-args', '--log-level', log_level],
remappings=remappings),
Node(
package='nav2_waypoint_follower',
executable='waypoint_follower',
name='waypoint_follower',
output='screen',
respawn=use_respawn,
respawn_delay=2.0,
parameters=[configured_params],
arguments=['--ros-args', '--log-level', log_level],
remappings=remappings),
Node(
package='nav2_velocity_smoother',
executable='velocity_smoother',
name='velocity_smoother',
output='screen',
respawn=use_respawn,
respawn_delay=2.0,
parameters=[configured_params],
arguments=['--ros-args', '--log-level', log_level],
remappings=remappings +
[('cmd_vel', 'cmd_vel_nav'), ('cmd_vel_smoothed', 'cmd_vel')]),
Node(
package='nav2_lifecycle_manager',
executable='lifecycle_manager',
name='lifecycle_manager_navigation',
output='screen',
arguments=['--ros-args', '--log-level', log_level],
parameters=[{'use_sim_time': use_sim_time},
{'autostart': autostart},
{'node_names': lifecycle_nodes}]),
]
)
load_composable_nodes = LoadComposableNodes(
condition=IfCondition(use_composition),
target_container=container_name_full,
composable_node_descriptions=[
ComposableNode(
package='nav2_controller',
plugin='nav2_controller::ControllerServer',
name='controller_server',
parameters=[configured_params],
remappings=remappings + [('cmd_vel', 'cmd_vel_nav')]),
ComposableNode(
package='nav2_smoother',
plugin='nav2_smoother::SmootherServer',
name='smoother_server',
parameters=[configured_params],
remappings=remappings),
ComposableNode(
package='nav2_planner',
plugin='nav2_planner::PlannerServer',
name='planner_server',
parameters=[configured_params],
remappings=remappings),
ComposableNode(
package='nav2_behaviors',
plugin='behavior_server::BehaviorServer',
name='behavior_server',
parameters=[configured_params],
remappings=remappings),
ComposableNode(
package='nav2_bt_navigator',
plugin='nav2_bt_navigator::BtNavigator',
name='bt_navigator',
parameters=[configured_params],
remappings=remappings),
ComposableNode(
package='nav2_waypoint_follower',
plugin='nav2_waypoint_follower::WaypointFollower',
name='waypoint_follower',
parameters=[configured_params],
remappings=remappings),
ComposableNode(
package='nav2_velocity_smoother',
plugin='nav2_velocity_smoother::VelocitySmoother',
name='velocity_smoother',
parameters=[configured_params],
remappings=remappings +
[('cmd_vel', 'cmd_vel_nav'), ('cmd_vel_smoothed', 'cmd_vel')]),
ComposableNode(
package='nav2_lifecycle_manager',
plugin='nav2_lifecycle_manager::LifecycleManager',
name='lifecycle_manager_navigation',
parameters=[{'use_sim_time': use_sim_time,
'autostart': autostart,
'node_names': lifecycle_nodes}]),
],
)
# Create the launch description and populate
ld = LaunchDescription()
# Set environment variables
ld.add_action(stdout_linebuf_envvar)
# Declare the launch options
ld.add_action(declare_namespace_cmd)
ld.add_action(declare_use_sim_time_cmd)
ld.add_action(declare_params_file_cmd)
ld.add_action(declare_autostart_cmd)
ld.add_action(declare_use_composition_cmd)
ld.add_action(declare_container_name_cmd)
ld.add_action(declare_use_respawn_cmd)
ld.add_action(declare_log_level_cmd)
# Add the actions to launch all of the navigation nodes
ld.add_action(load_nodes)
ld.add_action(load_composable_nodes)
return ld

View File

@ -0,0 +1,272 @@
# Copyright (c) 2018 Intel Corporation
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, GroupAction, SetEnvironmentVariable
from launch.conditions import IfCondition
from launch.substitutions import LaunchConfiguration, PythonExpression
from launch_ros.actions import LoadComposableNodes
from launch_ros.actions import Node
from launch_ros.descriptions import ComposableNode, ParameterFile
from nav2_common.launch import RewrittenYaml
def generate_launch_description():
# Get the launch directory
bringup_dir = get_package_share_directory('nav2_bringup')
namespace = LaunchConfiguration('namespace')
use_sim_time = LaunchConfiguration('use_sim_time')
autostart = LaunchConfiguration('autostart')
params_file = LaunchConfiguration('params_file')
use_composition = LaunchConfiguration('use_composition')
container_name = LaunchConfiguration('container_name')
container_name_full = (namespace, '/', container_name)
use_respawn = LaunchConfiguration('use_respawn')
log_level = LaunchConfiguration('log_level')
lifecycle_nodes = ['controller_server',
'smoother_server',
'planner_server',
'behavior_server',
'bt_navigator',
'waypoint_follower',
'velocity_smoother']
# Map fully qualified names to relative ones so the node's namespace can be prepended.
# In case of the transforms (tf), currently, there doesn't seem to be a better alternative
# https://github.com/ros/geometry2/issues/32
# https://github.com/ros/robot_state_publisher/pull/30
# TODO(orduno) Substitute with `PushNodeRemapping`
# https://github.com/ros2/launch_ros/issues/56
remappings = [('/tf', 'tf'),
('/tf_static', 'tf_static'),('/cmd_vel', '/go2/cmd_vel')]
# Create our own temporary YAML files that include substitutions
param_substitutions = {
'use_sim_time': use_sim_time,
'autostart': autostart}
configured_params = ParameterFile(
RewrittenYaml(
source_file=params_file,
root_key=namespace,
param_rewrites=param_substitutions,
convert_types=True),
allow_substs=True)
stdout_linebuf_envvar = SetEnvironmentVariable(
'RCUTILS_LOGGING_BUFFERED_STREAM', '1')
declare_namespace_cmd = DeclareLaunchArgument(
'namespace',
default_value='',
description='Top-level namespace')
declare_use_sim_time_cmd = DeclareLaunchArgument(
'use_sim_time',
default_value='false',
description='Use simulation (Gazebo) clock if true')
declare_params_file_cmd = DeclareLaunchArgument(
'params_file',
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(
'autostart', default_value='true',
description='Automatically startup the nav2 stack')
declare_use_composition_cmd = DeclareLaunchArgument(
'use_composition', default_value='False',
description='Use composed bringup if True')
declare_container_name_cmd = DeclareLaunchArgument(
'container_name', default_value='nav2_container',
description='the name of conatiner that nodes will load in if use composition')
declare_use_respawn_cmd = DeclareLaunchArgument(
'use_respawn', default_value='False',
description='Whether to respawn if a node crashes. Applied when composition is disabled.')
declare_log_level_cmd = DeclareLaunchArgument(
'log_level', default_value='info',
description='log level')
load_nodes = GroupAction(
condition=IfCondition(PythonExpression(['not ', use_composition])),
actions=[
Node(
package='nav2_controller',
executable='controller_server',
output='screen',
respawn=use_respawn,
respawn_delay=2.0,
parameters=[configured_params],
arguments=['--ros-args', '--log-level', log_level],
remappings=remappings + [('cmd_vel', 'cmd_vel_nav')]),
Node(
package='nav2_smoother',
executable='smoother_server',
name='smoother_server',
output='screen',
respawn=use_respawn,
respawn_delay=2.0,
parameters=[configured_params],
arguments=['--ros-args', '--log-level', log_level],
remappings=remappings),
Node(
package='nav2_planner',
executable='planner_server',
name='planner_server',
output='screen',
respawn=use_respawn,
respawn_delay=2.0,
parameters=[configured_params],
arguments=['--ros-args', '--log-level', log_level],
remappings=remappings),
Node(
package='nav2_behaviors',
executable='behavior_server',
name='behavior_server',
output='screen',
respawn=use_respawn,
respawn_delay=2.0,
parameters=[configured_params],
arguments=['--ros-args', '--log-level', log_level],
remappings=remappings),
Node(
package='nav2_bt_navigator',
executable='bt_navigator',
name='bt_navigator',
output='screen',
respawn=use_respawn,
respawn_delay=2.0,
parameters=[configured_params],
arguments=['--ros-args', '--log-level', log_level],
remappings=remappings),
Node(
package='nav2_waypoint_follower',
executable='waypoint_follower',
name='waypoint_follower',
output='screen',
respawn=use_respawn,
respawn_delay=2.0,
parameters=[configured_params],
arguments=['--ros-args', '--log-level', log_level],
remappings=remappings),
Node(
package='nav2_velocity_smoother',
executable='velocity_smoother',
name='velocity_smoother',
output='screen',
respawn=use_respawn,
respawn_delay=2.0,
parameters=[configured_params],
arguments=['--ros-args', '--log-level', log_level],
remappings=remappings +
[('cmd_vel', 'cmd_vel_nav'), ('cmd_vel_smoothed', 'cmd_vel')]),
Node(
package='nav2_lifecycle_manager',
executable='lifecycle_manager',
name='lifecycle_manager_navigation',
output='screen',
arguments=['--ros-args', '--log-level', log_level],
parameters=[{'use_sim_time': use_sim_time},
{'autostart': autostart},
{'node_names': lifecycle_nodes}]),
]
)
load_composable_nodes = LoadComposableNodes(
condition=IfCondition(use_composition),
target_container=container_name_full,
composable_node_descriptions=[
ComposableNode(
package='nav2_controller',
plugin='nav2_controller::ControllerServer',
name='controller_server',
parameters=[configured_params],
remappings=remappings + [('cmd_vel', 'cmd_vel_nav')]),
ComposableNode(
package='nav2_smoother',
plugin='nav2_smoother::SmootherServer',
name='smoother_server',
parameters=[configured_params],
remappings=remappings),
ComposableNode(
package='nav2_planner',
plugin='nav2_planner::PlannerServer',
name='planner_server',
parameters=[configured_params],
remappings=remappings),
ComposableNode(
package='nav2_behaviors',
plugin='behavior_server::BehaviorServer',
name='behavior_server',
parameters=[configured_params],
remappings=remappings),
ComposableNode(
package='nav2_bt_navigator',
plugin='nav2_bt_navigator::BtNavigator',
name='bt_navigator',
parameters=[configured_params],
remappings=remappings),
ComposableNode(
package='nav2_waypoint_follower',
plugin='nav2_waypoint_follower::WaypointFollower',
name='waypoint_follower',
parameters=[configured_params],
remappings=remappings),
ComposableNode(
package='nav2_velocity_smoother',
plugin='nav2_velocity_smoother::VelocitySmoother',
name='velocity_smoother',
parameters=[configured_params],
remappings=remappings +
[('cmd_vel', 'cmd_vel_nav'), ('cmd_vel_smoothed', 'cmd_vel')]),
ComposableNode(
package='nav2_lifecycle_manager',
plugin='nav2_lifecycle_manager::LifecycleManager',
name='lifecycle_manager_navigation',
parameters=[{'use_sim_time': use_sim_time,
'autostart': autostart,
'node_names': lifecycle_nodes}]),
],
)
# Create the launch description and populate
ld = LaunchDescription()
# Set environment variables
ld.add_action(stdout_linebuf_envvar)
# Declare the launch options
ld.add_action(declare_namespace_cmd)
ld.add_action(declare_use_sim_time_cmd)
ld.add_action(declare_params_file_cmd)
ld.add_action(declare_autostart_cmd)
ld.add_action(declare_use_composition_cmd)
ld.add_action(declare_container_name_cmd)
ld.add_action(declare_use_respawn_cmd)
ld.add_action(declare_log_level_cmd)
# Add the actions to launch all of the navigation nodes
ld.add_action(load_nodes)
ld.add_action(load_composable_nodes)
return ld

View File

@ -1,12 +1,12 @@
amcl: amcl:
ros__parameters: ros__parameters:
use_sim_time: False use_sim_time: True
alpha1: 0.2 alpha1: 0.2
alpha2: 0.2 alpha2: 0.2
alpha3: 0.2 alpha3: 0.2
alpha4: 0.2 alpha4: 0.2
alpha5: 0.2 alpha5: 0.2
base_frame_id: "base_link" base_frame_id: "base_footprint"
beam_skip_distance: 0.5 beam_skip_distance: 0.5
beam_skip_error_threshold: 0.9 beam_skip_error_threshold: 0.9
beam_skip_threshold: 0.3 beam_skip_threshold: 0.3
@ -26,7 +26,7 @@ amcl:
recovery_alpha_fast: 0.0 recovery_alpha_fast: 0.0
recovery_alpha_slow: 0.0 recovery_alpha_slow: 0.0
resample_interval: 1 resample_interval: 1
robot_model_type: "differential" robot_model_type: "nav2_amcl::DifferentialMotionModel"
save_pose_rate: 0.5 save_pose_rate: 0.5
sigma_hit: 0.2 sigma_hit: 0.2
tf_broadcast: true tf_broadcast: true
@ -37,63 +37,87 @@ amcl:
z_max: 0.05 z_max: 0.05
z_rand: 0.5 z_rand: 0.5
z_short: 0.05 z_short: 0.05
scan_topic: /go2/scan scan_topic: scan
amcl_map_client:
ros__parameters:
use_sim_time: False
amcl_rclcpp_node:
ros__parameters:
use_sim_time: False
bt_navigator: bt_navigator:
ros__parameters: ros__parameters:
use_sim_time: False use_sim_time: True
global_frame: map global_frame: map
robot_base_frame: base_link robot_base_frame: base_link
odom_topic: /utlidar/robot_odom odom_topic: /odom
enable_groot_monitoring: True bt_loop_duration: 10
groot_zmq_publisher_port: 1666 default_server_timeout: 20
groot_zmq_server_port: 1667 # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults:
default_bt_xml_filename: "navigate_w_replanning_and_recovery.xml" # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml
# nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml
# They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2.
plugin_lib_names: plugin_lib_names:
- nav2_compute_path_to_pose_action_bt_node - nav2_compute_path_to_pose_action_bt_node
- nav2_follow_path_action_bt_node - nav2_compute_path_through_poses_action_bt_node
- nav2_back_up_action_bt_node - nav2_smooth_path_action_bt_node
- nav2_spin_action_bt_node - nav2_follow_path_action_bt_node
- nav2_wait_action_bt_node - nav2_spin_action_bt_node
- nav2_clear_costmap_service_bt_node - nav2_wait_action_bt_node
- nav2_is_stuck_condition_bt_node - nav2_assisted_teleop_action_bt_node
- nav2_goal_reached_condition_bt_node - nav2_back_up_action_bt_node
- nav2_goal_updated_condition_bt_node - nav2_drive_on_heading_bt_node
- nav2_initial_pose_received_condition_bt_node - nav2_clear_costmap_service_bt_node
- nav2_reinitialize_global_localization_service_bt_node - nav2_is_stuck_condition_bt_node
- nav2_rate_controller_bt_node - nav2_goal_reached_condition_bt_node
- nav2_distance_controller_bt_node - nav2_goal_updated_condition_bt_node
- nav2_speed_controller_bt_node - nav2_globally_updated_goal_condition_bt_node
- nav2_truncate_path_action_bt_node - nav2_is_path_valid_condition_bt_node
- nav2_goal_updater_node_bt_node - nav2_initial_pose_received_condition_bt_node
- nav2_recovery_node_bt_node - nav2_reinitialize_global_localization_service_bt_node
- nav2_pipeline_sequence_bt_node - nav2_rate_controller_bt_node
- nav2_round_robin_node_bt_node - nav2_distance_controller_bt_node
- nav2_transform_available_condition_bt_node - nav2_speed_controller_bt_node
- nav2_time_expired_condition_bt_node - nav2_truncate_path_action_bt_node
- nav2_distance_traveled_condition_bt_node - nav2_truncate_path_local_action_bt_node
- nav2_goal_updater_node_bt_node
- nav2_recovery_node_bt_node
- nav2_pipeline_sequence_bt_node
- nav2_round_robin_node_bt_node
- nav2_transform_available_condition_bt_node
- nav2_time_expired_condition_bt_node
- nav2_path_expiring_timer_condition
- nav2_distance_traveled_condition_bt_node
- nav2_single_trigger_bt_node
- nav2_goal_updated_controller_bt_node
- nav2_is_battery_low_condition_bt_node
- nav2_navigate_through_poses_action_bt_node
- nav2_navigate_to_pose_action_bt_node
- nav2_remove_passed_goals_action_bt_node
- nav2_planner_selector_bt_node
- nav2_controller_selector_bt_node
- nav2_goal_checker_selector_bt_node
- nav2_controller_cancel_bt_node
- nav2_path_longer_on_approach_bt_node
- nav2_wait_cancel_bt_node
- nav2_spin_cancel_bt_node
- nav2_back_up_cancel_bt_node
- nav2_assisted_teleop_cancel_bt_node
- nav2_drive_on_heading_cancel_bt_node
- nav2_is_battery_charging_condition_bt_node
bt_navigator_rclcpp_node: bt_navigator_navigate_through_poses_rclcpp_node:
ros__parameters: ros__parameters:
use_sim_time: False use_sim_time: True
bt_navigator_navigate_to_pose_rclcpp_node:
ros__parameters:
use_sim_time: True
controller_server: controller_server:
ros__parameters: ros__parameters:
use_sim_time: False use_sim_time: True
controller_frequency: 20.0 controller_frequency: 20.0
min_x_velocity_threshold: 0.001 min_x_velocity_threshold: 0.001
min_y_velocity_threshold: 0.5 min_y_velocity_threshold: 0.5
min_theta_velocity_threshold: 0.001 min_theta_velocity_threshold: 0.001
failure_tolerance: 0.3
progress_checker_plugin: "progress_checker" progress_checker_plugin: "progress_checker"
goal_checker_plugin: "goal_checker" goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker"
controller_plugins: ["FollowPath"] controller_plugins: ["FollowPath"]
# Progress checker parameters # Progress checker parameters
@ -102,11 +126,16 @@ controller_server:
required_movement_radius: 0.5 required_movement_radius: 0.5
movement_time_allowance: 10.0 movement_time_allowance: 10.0
# Goal checker parameters # Goal checker parameters
goal_checker: #precise_goal_checker:
# plugin: "nav2_controller::SimpleGoalChecker"
# xy_goal_tolerance: 0.25
# yaw_goal_tolerance: 0.25
# stateful: True
general_goal_checker:
stateful: True
plugin: "nav2_controller::SimpleGoalChecker" plugin: "nav2_controller::SimpleGoalChecker"
xy_goal_tolerance: 0.25 xy_goal_tolerance: 0.25
yaw_goal_tolerance: 0.25 yaw_goal_tolerance: 0.25
stateful: True
# DWB parameters # DWB parameters
FollowPath: FollowPath:
plugin: "dwb_core::DWBLocalPlanner" plugin: "dwb_core::DWBLocalPlanner"
@ -150,10 +179,6 @@ controller_server:
RotateToGoal.slowing_factor: 5.0 RotateToGoal.slowing_factor: 5.0
RotateToGoal.lookahead_time: -1.0 RotateToGoal.lookahead_time: -1.0
controller_server_rclcpp_node:
ros__parameters:
use_sim_time: False
local_costmap: local_costmap:
local_costmap: local_costmap:
ros__parameters: ros__parameters:
@ -161,7 +186,7 @@ local_costmap:
publish_frequency: 2.0 publish_frequency: 2.0
global_frame: odom global_frame: odom
robot_base_frame: base_link robot_base_frame: base_link
use_sim_time: False use_sim_time: True
rolling_window: true rolling_window: true
width: 3 width: 3
height: 3 height: 3
@ -188,15 +213,14 @@ local_costmap:
clearing: True clearing: True
marking: True marking: True
data_type: "LaserScan" data_type: "LaserScan"
raytrace_max_range: 3.0
raytrace_min_range: 0.0
obstacle_max_range: 2.5
obstacle_min_range: 0.0
static_layer: static_layer:
plugin: "nav2_costmap_2d::StaticLayer"
map_subscribe_transient_local: True map_subscribe_transient_local: True
always_send_full_costmap: True always_send_full_costmap: True
local_costmap_client:
ros__parameters:
use_sim_time: False
local_costmap_rclcpp_node:
ros__parameters:
use_sim_time: False
global_costmap: global_costmap:
global_costmap: global_costmap:
@ -205,10 +229,10 @@ global_costmap:
publish_frequency: 1.0 publish_frequency: 1.0
global_frame: map global_frame: map
robot_base_frame: base_link robot_base_frame: base_link
use_sim_time: False use_sim_time: True
robot_radius: 0.22 robot_radius: 0.22
resolution: 0.05 resolution: 0.05
track_unknown_space: true track_unknown_space: false
plugins: ["static_layer", "obstacle_layer", "inflation_layer"] plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
obstacle_layer: obstacle_layer:
plugin: "nav2_costmap_2d::ObstacleLayer" plugin: "nav2_costmap_2d::ObstacleLayer"
@ -220,6 +244,10 @@ global_costmap:
clearing: True clearing: True
marking: True marking: True
data_type: "LaserScan" data_type: "LaserScan"
raytrace_max_range: 3.0
raytrace_min_range: 0.0
obstacle_max_range: 2.5
obstacle_min_range: 0.0
static_layer: static_layer:
plugin: "nav2_costmap_2d::StaticLayer" plugin: "nav2_costmap_2d::StaticLayer"
map_subscribe_transient_local: True map_subscribe_transient_local: True
@ -228,30 +256,26 @@ global_costmap:
cost_scaling_factor: 3.0 cost_scaling_factor: 3.0
inflation_radius: 0.55 inflation_radius: 0.55
always_send_full_costmap: True always_send_full_costmap: True
global_costmap_client:
ros__parameters:
use_sim_time: False
global_costmap_rclcpp_node:
ros__parameters:
use_sim_time: False
map_server: map_server:
ros__parameters: ros__parameters:
use_sim_time: False use_sim_time: True
yaml_filename: "/home/unitree/Generated_Maps/basement/hallway-basement.yaml" # Overridden in launch by the "map" launch configuration or provided default value.
# To use in yaml, remove the default "map" value in the tb3_simulation_launch.py file & provide full path to map below.
yaml_filename: ""
map_saver: map_saver:
ros__parameters: ros__parameters:
use_sim_time: False use_sim_time: True
save_map_timeout: 5000 save_map_timeout: 5.0
free_thresh_default: 0.25 free_thresh_default: 0.25
occupied_thresh_default: 0.65 occupied_thresh_default: 0.65
map_subscribe_transient_local: False map_subscribe_transient_local: True
planner_server: planner_server:
ros__parameters: ros__parameters:
expected_planner_frequency: 20.0 expected_planner_frequency: 20.0
use_sim_time: False use_sim_time: True
planner_plugins: ["GridBased"] planner_plugins: ["GridBased"]
GridBased: GridBased:
plugin: "nav2_navfn_planner/NavfnPlanner" plugin: "nav2_navfn_planner/NavfnPlanner"
@ -259,26 +283,36 @@ planner_server:
use_astar: false use_astar: false
allow_unknown: true allow_unknown: true
planner_server_rclcpp_node: smoother_server:
ros__parameters: ros__parameters:
use_sim_time: False use_sim_time: True
smoother_plugins: ["simple_smoother"]
simple_smoother:
plugin: "nav2_smoother::SimpleSmoother"
tolerance: 1.0e-10
max_its: 1000
do_refinement: True
recoveries_server: behavior_server:
ros__parameters: ros__parameters:
costmap_topic: local_costmap/costmap_raw costmap_topic: local_costmap/costmap_raw
footprint_topic: local_costmap/published_footprint footprint_topic: local_costmap/published_footprint
cycle_frequency: 10.0 cycle_frequency: 10.0
recovery_plugins: ["spin", "back_up", "wait"] behavior_plugins: ["spin", "backup", "drive_on_heading", "assisted_teleop", "wait"]
spin: spin:
plugin: "nav2_recoveries/Spin" plugin: "nav2_behaviors/Spin"
back_up: backup:
plugin: "nav2_recoveries/BackUp" plugin: "nav2_behaviors/BackUp"
drive_on_heading:
plugin: "nav2_behaviors/DriveOnHeading"
wait: wait:
plugin: "nav2_recoveries/Wait" plugin: "nav2_behaviors/Wait"
assisted_teleop:
plugin: "nav2_behaviors/AssistedTeleop"
global_frame: odom global_frame: odom
robot_base_frame: base_link robot_base_frame: base_link
transform_timeout: 0.1 transform_tolerance: 0.1
use_sim_time: False use_sim_time: true
simulate_ahead_time: 2.0 simulate_ahead_time: 2.0
max_rotational_vel: 1.0 max_rotational_vel: 1.0
min_rotational_vel: 0.4 min_rotational_vel: 0.4
@ -286,4 +320,30 @@ recoveries_server:
robot_state_publisher: robot_state_publisher:
ros__parameters: ros__parameters:
use_sim_time: False use_sim_time: True
waypoint_follower:
ros__parameters:
use_sim_time: True
loop_rate: 20
stop_on_failure: false
waypoint_task_executor_plugin: "wait_at_waypoint"
wait_at_waypoint:
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
enabled: True
waypoint_pause_duration: 200
velocity_smoother:
ros__parameters:
use_sim_time: True
smoothing_frequency: 20.0
scale_velocities: False
feedback: "OPEN_LOOP"
max_velocity: [0.26, 0.0, 1.0]
min_velocity: [-0.26, 0.0, -1.0]
max_accel: [2.5, 0.0, 3.2]
max_decel: [-2.5, 0.0, -3.2]
odom_topic: "odom"
odom_duration: 0.1
deadband_velocity: [0.0, 0.0, 0.0]
velocity_timeout: 1.0

1
nav2_docker_run.sh Executable file
View File

@ -0,0 +1 @@
docker run --rm -it --privileged --network host -v $(pwd)/deploy/nav2_ws/src:/home/nav2_ws/src -v /dev/*:/dev/* -v /etc/localtime:/etc/localtime:ro --runtime nvidia go2py_nav:latest