Nav2源码阅读(一)nav2

阅读: 评论:0

Nav2源码阅读(一)nav2

Nav2源码阅读(一)nav2

ros2 launch nav2_bringup tb3_simulation_launch.py
通过这个脚本就可以启动最简单的导航仿真,我们来分析一下这个整个过程是怎么启动的。

# 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
#
#     .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."""This is all-in-one launch script intended for use by nav2 developers."""import osfrom ament_index_python.packages import get_package_share_directoryfrom launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, ExecuteProcess, IncludeLaunchDescription
ditions import IfCondition
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration, PythonExpression
from launch_ros.actions import Nodedef generate_launch_description():# Get the launch directorybringup_dir = get_package_share_directory('nav2_bringup')launch_dir = os.path.join(bringup_dir, 'launch')# Create the launch configuration variablesslam = LaunchConfiguration('slam')namespace = LaunchConfiguration('namespace')use_namespace = LaunchConfiguration('use_namespace')map_yaml_file = LaunchConfiguration('map')use_sim_time = LaunchConfiguration('use_sim_time')params_file = LaunchConfiguration('params_file')autostart = LaunchConfiguration('autostart')# Launch configuration variables specific to simulationrviz_config_file = LaunchConfiguration('rviz_config_file')use_simulator = LaunchConfiguration('use_simulator')use_robot_state_pub = LaunchConfiguration('use_robot_state_pub')use_rviz = LaunchConfiguration('use_rviz')headless = LaunchConfiguration('headless')world = LaunchConfiguration('world')# 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#   TODO(orduno) Substitute with `PushNodeRemapping`#               = [('/tf', 'tf'),('/tf_static', 'tf_static')]# Declare the launch argumentsdeclare_namespace_cmd = DeclareLaunchArgument('namespace',default_value='',description='Top-level namespace')declare_use_namespace_cmd = DeclareLaunchArgument('use_namespace',default_value='false',description='Whether to apply a namespace to the navigation stack')declare_slam_cmd = DeclareLaunchArgument('slam',default_value='False',description='Whether run a SLAM')declare_map_yaml_cmd = DeclareLaunchArgument('map',default_value=os.path.join(bringup_dir, 'maps', 'turtlebot3_world.yaml'),description='Full path to map file to load')declare_use_sim_time_cmd = DeclareLaunchArgument('use_sim_time',default_value='true',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')# 自动加载nav2 stackdeclare_autostart_cmd = DeclareLaunchArgument('autostart', default_value='true',description='Automatically startup the nav2 stack')declare_rviz_config_file_cmd = DeclareLaunchArgument('rviz_config_file',default_value=os.path.join(bringup_dir, 'rviz', 'nav2_default_view.rviz'),description='Full path to the RVIZ config file to use')declare_use_simulator_cmd = DeclareLaunchArgument('use_simulator',default_value='True',description='Whether to start the simulator')# 是否使用状态发布declare_use_robot_state_pub_cmd = DeclareLaunchArgument('use_robot_state_pub',default_value='True',description='Whether to start the robot state publisher')declare_use_rviz_cmd = DeclareLaunchArgument('use_rviz',default_value='True',description='Whether to start RVIZ')declare_simulator_cmd = DeclareLaunchArgument('headless',default_value='False',description='Whether to execute gzclient)')declare_world_cmd = DeclareLaunchArgument('world',# TODO(orduno) Switch back once ROS argument passing has been fixed upstream#               default_value=os.path.join(get_package_share_directory('turtlebot3_gazebo'),# worlds/turtlebot3_del')default_value=os.path.join(bringup_dir, 'worlds', &#del'),description='Full path to world model file to load')# Specify the actionsstart_gazebo_server_cmd = ExecuteProcess(condition=IfCondition(use_simulator),cmd=['gzserver', '-s', 'libgazebo_ros_init.so', world],cwd=[launch_dir], output='screen')start_gazebo_client_cmd = ExecuteProcess(condition=IfCondition(PythonExpression([use_simulator, ' and not ', headless])),cmd=['gzclient'],cwd=[launch_dir], output='screen')urdf = os.path.join(bringup_dir, 'urdf', 'turtlebot3_waffle.urdf')# 启动robot state publisherstart_robot_state_publisher_cmd = Node(condition=IfCondition(use_robot_state_pub),package='robot_state_publisher',executable='robot_state_publisher',name='robot_state_publisher',namespace=namespace,output='screen',parameters=[{'use_sim_time': use_sim_time}],remappings=remappings,arguments=[urdf])# 通过脚本启动rviz    rviz_cmd = IncludeLaunchDescription(PythonLaunchDescriptionSource(os.path.join(launch_dir, 'rviz_launch.py')),condition=IfCondition(use_rviz),launch_arguments={'namespace': '','use_namespace': 'False','rviz_config': rviz_config_file}.items())# 通过脚本启动bringup, 这个脚本使用了上边设置的一些参数bringup_cmd = IncludeLaunchDescription(PythonLaunchDescriptionSource(os.path.join(launch_dir, 'bringup_launch.py')),launch_arguments={'namespace': namespace,'use_namespace': use_namespace,'slam': slam,'map': map_yaml_file,'use_sim_time': use_sim_time,'params_file': params_file,'autostart': autostart}.items())# Create the launch description and populateld = LaunchDescription()# Declare the launch optionsld.add_action(declare_namespace_cmd)ld.add_action(declare_use_namespace_cmd)ld.add_action(declare_slam_cmd)ld.add_action(declare_map_yaml_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_rviz_config_file_cmd)ld.add_action(declare_use_simulator_cmd)ld.add_action(declare_use_robot_state_pub_cmd)ld.add_action(declare_use_rviz_cmd)ld.add_action(declare_simulator_cmd)ld.add_action(declare_world_cmd)# Add any conditioned actionsld.add_action(start_gazebo_server_cmd)ld.add_action(start_gazebo_client_cmd)# Add the actions to launch all of the navigation nodesld.add_action(start_robot_state_publisher_cmd)ld.add_action(rviz_cmd)ld.add_action(bringup_cmd)return ld

脚本里关于gazebo的我们先不看,这个脚本实际启动了3个东西

1.  robot state publisher

2.  rviz_launch.py

3.  bringup_launch.py

robot_state_publisher加载一个urdf就好了,这个比较简单, rviz先不看, 那么看bringup

# 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
#
#     .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 osfrom ament_index_python.packages import get_package_share_directoryfrom launch import LaunchDescription
from launch.actions import (DeclareLaunchArgument, GroupAction,IncludeLaunchDescription, SetEnvironmentVariable)
ditions import IfCondition
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration, PythonExpression
from launch_ros.actions import PushRosNamespacedef generate_launch_description():# Get the launch directorybringup_dir = get_package_share_directory('nav2_bringup')launch_dir = os.path.join(bringup_dir, 'launch')# Create the launch configuration variablesnamespace = LaunchConfiguration('namespace')use_namespace = LaunchConfiguration('use_namespace')slam = LaunchConfiguration('slam')map_yaml_file = LaunchConfiguration('map')use_sim_time = LaunchConfiguration('use_sim_time')params_file = LaunchConfiguration('params_file')autostart = LaunchConfiguration('autostart')stdout_linebuf_envvar = SetEnvironmentVariable('RCUTILS_LOGGING_BUFFERED_STREAM', '1')declare_namespace_cmd = DeclareLaunchArgument('namespace',default_value='',description='Top-level namespace')declare_use_namespace_cmd = DeclareLaunchArgument('use_namespace',default_value='false',description='Whether to apply a namespace to the navigation stack')declare_slam_cmd = DeclareLaunchArgument('slam',default_value='False',description='Whether run a SLAM')declare_map_yaml_cmd = DeclareLaunchArgument('map',description='Full path to map yaml file to load')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')# 这里启动了分别 slam, 定位,导航# Specify the actionsbringup_cmd_group = GroupAction([PushRosNamespace(condition=IfCondition(use_namespace),namespace=namespace),IncludeLaunchDescription(PythonLaunchDescriptionSource(os.path.join(launch_dir, 'slam_launch.py')),condition=IfCondition(slam),launch_arguments={'namespace': namespace,'use_sim_time': use_sim_time,'autostart': autostart,'params_file': params_file}.items()),IncludeLaunchDescription(PythonLaunchDescriptionSource(os.path.join(launch_dir,'localization_launch.py')),condition=IfCondition(PythonExpression(['not ', slam])),launch_arguments={'namespace': namespace,'map': map_yaml_file,'use_sim_time': use_sim_time,'autostart': autostart,'params_file': params_file,'use_lifecycle_mgr': 'false'}.items()),IncludeLaunchDescription(PythonLaunchDescriptionSource(os.path.join(launch_dir, 'navigation_launch.py')),launch_arguments={'namespace': namespace,'use_sim_time': use_sim_time,'autostart': autostart,'params_file': params_file,'use_lifecycle_mgr': 'false','map_subscribe_transient_local': 'true'}.items()),])# Create the launch description and populateld = LaunchDescription()# Set environment variablesld.add_action(stdout_linebuf_envvar)# Declare the launch optionsld.add_action(declare_namespace_cmd)ld.add_action(declare_use_namespace_cmd)ld.add_action(declare_slam_cmd)ld.add_action(declare_map_yaml_cmd)ld.add_action(declare_use_sim_time_cmd)ld.add_action(declare_params_file_cmd)ld.add_action(declare_autostart_cmd)# Add the actions to launch all of the navigation nodesld.add_action(bringup_cmd_group)return ld

这个脚本里又启动了另外三个脚本,也就是我们机器人需要用到的三大核心功能:

1.  slam_launch.py

2.  localization_launch.py

3.  navigation_launch.py

slam里启动了一个map_server,我们先不看,看localization

# 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
#
#     .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 osfrom ament_index_python.packages import get_package_share_directoryfrom launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, SetEnvironmentVariable
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
from nav2_common.launch import RewrittenYamldef generate_launch_description():# Get the launch directorybringup_dir = get_package_share_directory('nav2_bringup')namespace = LaunchConfiguration('namespace')map_yaml_file = LaunchConfiguration('map')use_sim_time = LaunchConfiguration('use_sim_time')autostart = LaunchConfiguration('autostart')params_file = LaunchConfiguration('params_file')lifecycle_nodes = ['map_server', 'amcl']# 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#   TODO(orduno) Substitute with `PushNodeRemapping`#               = [('/tf', 'tf'),('/tf_static', 'tf_static')]# Create our own temporary YAML files that include substitutionsparam_substitutions = {'use_sim_time': use_sim_time,'yaml_filename': map_yaml_file}configured_params = RewrittenYaml(source_file=params_file,root_key=namespace,param_rewrites=param_substitutions,convert_types=True)return LaunchDescription([# Set env var to print messages to stdout immediatelySetEnvironmentVariable('RCUTILS_LOGGING_BUFFERED_STREAM', '1'),DeclareLaunchArgument('namespace', default_value='',description='Top-level namespace'),DeclareLaunchArgument('map',default_value=os.path.join(bringup_dir, 'maps', 'turtlebot3_world.yaml'),description='Full path to map yaml file to load'),DeclareLaunchArgument('use_sim_time', default_value='false',description='Use simulation (Gazebo) clock if true'),DeclareLaunchArgument('autostart', default_value='true',description='Automatically startup the nav2 stack'),DeclareLaunchArgument('params_file',default_value=os.path.join(bringup_dir, 'params', 'nav2_params.yaml'),description='Full path to the ROS2 parameters file to use'),Node(package='nav2_map_server',executable='map_server',name='map_server',output='screen',parameters=[configured_params],remappings=remappings),Node(package='nav2_amcl',executable='amcl',name='amcl',output='screen',parameters=[configured_params],remappings=remappings),Node(package='nav2_lifecycle_manager',executable='lifecycle_manager',name='lifecycle_manager_localization',output='screen',parameters=[{'use_sim_time': use_sim_time},{'autostart': autostart},{'node_names': lifecycle_nodes}])])

这里启动了三个node:

1.  map_server

2.  amcl

3.  lifecycle_manager

这个也先不看了,我们想知道控制相关的东西,这里并没有,我们去看navigation:

# 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
#
#     .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 osfrom ament_index_python.packages import get_package_share_directoryfrom launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, SetEnvironmentVariable
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
from nav2_common.launch import RewrittenYamldef generate_launch_description():# Get the launch directorybringup_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')lifecycle_nodes = ['controller_server','planner_server','recoveries_server','bt_navigator','waypoint_follower']# 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#   TODO(orduno) Substitute with `PushNodeRemapping`#               = [('/tf', 'tf'),('/tf_static', 'tf_static')]# Create our own temporary YAML files that include substitutionsparam_substitutions = {'use_sim_time': use_sim_time,'autostart': autostart}configured_params = RewrittenYaml(source_file=params_file,root_key=namespace,param_rewrites=param_substitutions,convert_types=True)return LaunchDescription([# Set env var to print messages to stdout immediatelySetEnvironmentVariable('RCUTILS_LOGGING_BUFFERED_STREAM', '1'),DeclareLaunchArgument('namespace', default_value='',description='Top-level namespace'),DeclareLaunchArgument('use_sim_time', default_value='false',description='Use simulation (Gazebo) clock if true'),DeclareLaunchArgument('autostart', default_value='true',description='Automatically startup the nav2 stack'),DeclareLaunchArgument('params_file',default_value=os.path.join(bringup_dir, 'params', 'nav2_params.yaml'),description='Full path to the ROS2 parameters file to use'),# 这里生成了一个costmap_ros节点local_costmap,而这个节点会调用各种cosmap2d插件Node(package='nav2_controller',executable='controller_server',output='screen',parameters=[configured_params],remappings=remappings),# 这里生成了一个costmap_ros节点global_costmapNode(package='nav2_planner',executable='planner_server',name='planner_server',output='screen',parameters=[configured_params],remappings=remappings),Node(package='nav2_recoveries',executable='recoveries_server',name='recoveries_server',output='screen',parameters=[configured_params],remappings=remappings),Node(package='nav2_bt_navigator',executable='bt_navigator',name='bt_navigator',output='screen',parameters=[configured_params],remappings=remappings),Node(package='nav2_waypoint_follower',executable='waypoint_follower',name='waypoint_follower',output='screen',parameters=[configured_params],remappings=remappings),Node(package='nav2_lifecycle_manager',executable='lifecycle_manager',name='lifecycle_manager_navigation',output='screen',parameters=[{'use_sim_time': use_sim_time},{'autostart': autostart},{'node_names': lifecycle_nodes}]),])

这里启动了5个节点:

1.  controller_server        (local)

2.  planner_server        (global)

3.  recoveries_server

4.  bt_navigator

5.  waypoint_follower

6.  lifecycle_manager

其中: controller_server、planner_server、recoveries_server 是最基本的三个底层节点.html  。

bt_navigator、waypoint_follower  这两个是相对高层次的节点,先研究底层的三个。

        DeclareLaunchArgument('params_file',default_value=os.path.join(bringup_dir, 'params', 'nav2_params.yaml'),description='Full path to the ROS2 parameters file to use'),

这里可以看到参数是通过yaml文件加载进来的

amcl:ros__parameters:use_sim_time: Truealpha1: 0.2alpha2: 0.2alpha3: 0.2alpha4: 0.2alpha5: 0.2base_frame_id: "base_footprint"beam_skip_distance: 0.5beam_skip_error_threshold: 0.9beam_skip_threshold: 0.3do_beamskip: falseglobal_frame_id: "map"lambda_short: 0.1laser_likelihood_max_dist: 2.0laser_max_range: 100.0laser_min_range: -1.0laser_model_type: "likelihood_field"max_beams: 60max_particles: 2000min_particles: 500odom_frame_id: "odom"pf_err: 0.05pf_z: 0.99recovery_alpha_fast: 0.0recovery_alpha_slow: 0.0resample_interval: 1robot_model_type: "differential"save_pose_rate: 0.5sigma_hit: 0.2tf_broadcast: truetransform_tolerance: 1.0update_min_a: 0.2update_min_d: 0.25z_hit: 0.5z_max: 0.05z_rand: 0.5z_short: 0.05scan_topic: scanamcl_map_client:ros__parameters:use_sim_time: Trueamcl_rclcpp_node:ros__parameters:use_sim_time: Truebt_navigator:ros__parameters:use_sim_time: Trueglobal_frame: maprobot_base_frame: base_linkodom_topic: /odombt_loop_duration: 10default_server_timeout: 20enable_groot_monitoring: Truegroot_zmq_publisher_port: 1666groot_zmq_server_port: 1667# 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults:# nav2_bt_navigator/navigate_to_pose_w_replanning_l# nav2_bt_navigator/navigate_through_poses_w_replanning_l# They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2.plugin_lib_names:- nav2_compute_path_to_pose_action_bt_node- nav2_compute_path_through_poses_action_bt_node- nav2_follow_path_action_bt_node- nav2_back_up_action_bt_node- nav2_spin_action_bt_node- nav2_wait_action_bt_node- nav2_clear_costmap_service_bt_node- nav2_is_stuck_condition_bt_node- nav2_goal_reached_condition_bt_node- nav2_goal_updated_condition_bt_node- nav2_initial_pose_received_condition_bt_node- nav2_reinitialize_global_localization_service_bt_node- nav2_rate_controller_bt_node- nav2_distance_controller_bt_node- nav2_speed_controller_bt_node- nav2_truncate_path_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_distance_traveled_condition_bt_node- nav2_single_trigger_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_nodebt_navigator_rclcpp_node:ros__parameters:use_sim_time: Truecontroller_server:ros__parameters:use_sim_time: Truecontroller_frequency: 20.0min_x_velocity_threshold: 0.001min_y_velocity_threshold: 0.5min_theta_velocity_threshold: 0.001failure_tolerance: 0.3progress_checker_plugin: "progress_checker"goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker"controller_plugins: ["FollowPath"]# Progress checker parametersprogress_checker:plugin: "nav2_controller::SimpleProgressChecker"required_movement_radius: 0.5movement_time_allowance: 10.0# Goal checker parameters#precise_goal_checker:#  plugin: "nav2_controller::SimpleGoalChecker"#  xy_goal_tolerance: 0.25#  yaw_goal_tolerance: 0.25#  stateful: Truegeneral_goal_checker:stateful: Trueplugin: "nav2_controller::SimpleGoalChecker"xy_goal_tolerance: 0.25yaw_goal_tolerance: 0.25# DWB parametersFollowPath:plugin: "dwb_core::DWBLocalPlanner"debug_trajectory_details: Truemin_vel_x: 0.0min_vel_y: 0.0max_vel_x: 0.26max_vel_y: 0.0max_vel_theta: 1.0min_speed_xy: 0.0max_speed_xy: 0.26min_speed_theta: 0.0# Add high threshold velocity for turtlebot 3 issue.# : 2.5acc_lim_y: 0.0acc_lim_theta: 3.2decel_lim_x: -2.5decel_lim_y: 0.0decel_lim_theta: -3.2vx_samples: 20vy_samples: 5vtheta_samples: 20sim_time: 1.7linear_granularity: 0.05angular_granularity: 0.025transform_tolerance: 0.2xy_goal_tolerance: 0.25trans_stopped_velocity: 0.25short_circuit_trajectory_evaluation: Truestateful: Truecritics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]BaseObstacle.scale: 0.02PathAlign.scale: 32.0PathAlign.forward_point_distance: 0.1GoalAlign.scale: 24.0GoalAlign.forward_point_distance: 0.1PathDist.scale: 32.0GoalDist.scale: 24.0RotateToGoal.scale: 32.0RotateToGoal.slowing_factor: 5.0RotateToGoal.lookahead_time: -1.0controller_server_rclcpp_node:ros__parameters:use_sim_time: Truelocal_costmap:local_costmap:ros__parameters:update_frequency: 5.0publish_frequency: 2.0global_frame: odomrobot_base_frame: base_linkuse_sim_time: Truerolling_window: truewidth: 3height: 3resolution: 0.05robot_radius: 0.22plugins: ["voxel_layer", "inflation_layer"]inflation_layer:plugin: "nav2_costmap_2d::InflationLayer"cost_scaling_factor: 3.0inflation_radius: 0.55voxel_layer:plugin: "nav2_costmap_2d::VoxelLayer"enabled: Truepublish_voxel_map: Trueorigin_z: 0.0z_resolution: 0.05z_voxels: 16max_obstacle_height: 2.0mark_threshold: 0observation_sources: scanscan:topic: /scanmax_obstacle_height: 2.0clearing: Truemarking: Truedata_type: "LaserScan"raytrace_max_range: 3.0raytrace_min_range: 0.0obstacle_max_range: 2.5obstacle_min_range: 0.0static_layer:map_subscribe_transient_local: Truealways_send_full_costmap: Truelocal_costmap_client:ros__parameters:use_sim_time: Truelocal_costmap_rclcpp_node:ros__parameters:use_sim_time: Trueglobal_costmap:global_costmap:ros__parameters:update_frequency: 1.0publish_frequency: 1.0global_frame: maprobot_base_frame: base_linkuse_sim_time: Truerobot_radius: 0.22resolution: 0.05track_unknown_space: trueplugins: ["static_layer", "obstacle_layer", "inflation_layer"]obstacle_layer:plugin: "nav2_costmap_2d::ObstacleLayer"enabled: Trueobservation_sources: scanscan:topic: /scanmax_obstacle_height: 2.0clearing: Truemarking: Truedata_type: "LaserScan"raytrace_max_range: 3.0raytrace_min_range: 0.0obstacle_max_range: 2.5obstacle_min_range: 0.0static_layer:plugin: "nav2_costmap_2d::StaticLayer"map_subscribe_transient_local: Trueinflation_layer:plugin: "nav2_costmap_2d::InflationLayer"cost_scaling_factor: 3.0inflation_radius: 0.55always_send_full_costmap: Trueglobal_costmap_client:ros__parameters:use_sim_time: Trueglobal_costmap_rclcpp_node:ros__parameters:use_sim_time: Truemap_server:ros__parameters:use_sim_time: Trueyaml_filename: "turtlebot3_world.yaml"map_saver:ros__parameters:use_sim_time: Truesave_map_timeout: 5.0free_thresh_default: 0.25occupied_thresh_default: 0.65map_subscribe_transient_local: Trueplanner_server:ros__parameters:expected_planner_frequency: 20.0use_sim_time: Trueplanner_plugins: ["GridBased"]GridBased:plugin: "nav2_navfn_planner/NavfnPlanner"tolerance: 0.5use_astar: falseallow_unknown: trueplanner_server_rclcpp_node:ros__parameters:use_sim_time: Truerecoveries_server:ros__parameters:costmap_topic: local_costmap/costmap_rawfootprint_topic: local_costmap/published_footprintcycle_frequency: 10.0recovery_plugins: ["spin", "backup", "wait"]spin:plugin: "nav2_recoveries/Spin"backup:plugin: "nav2_recoveries/BackUp"wait:plugin: "nav2_recoveries/Wait"global_frame: odomrobot_base_frame: base_linktransform_timeout: 0.1use_sim_time: truesimulate_ahead_time: 2.0max_rotational_vel: 1.0min_rotational_vel: 0.4rotational_acc_lim: 3.2robot_state_publisher:ros__parameters:use_sim_time: Truewaypoint_follower:ros__parameters:loop_rate: 20stop_on_failure: falsewaypoint_task_executor_plugin: "wait_at_waypoint"   wait_at_waypoint:plugin: "nav2_waypoint_follower::WaitAtWaypoint"enabled: Truewaypoint_pause_duration: 200

按照逻辑,机器人需要先进行全局规划,再进行局部规划,所以我们应该先看planner,再看controller,如果stuck了,还需要进行recover

本文发布于:2024-01-31 17:57:37,感谢您对本站的认可!

本文链接:https://www.4u4v.net/it/170669505730330.html

版权声明:本站内容均来自互联网,仅供演示用,请勿用于商业和其他非法用途。如果侵犯了您的权益请与我们联系,我们将在24小时内删除。

标签:源码
留言与评论(共有 0 条评论)
   
验证码:

Copyright ©2019-2022 Comsenz Inc.Powered by ©

网站地图1 网站地图2 网站地图3 网站地图4 网站地图5 网站地图6 网站地图7 网站地图8 网站地图9 网站地图10 网站地图11 网站地图12 网站地图13 网站地图14 网站地图15 网站地图16 网站地图17 网站地图18 网站地图19 网站地图20 网站地图21 网站地图22/a> 网站地图23