Skip to content
Snippets Groups Projects
Commit 1efe19f0 authored by Michael Jeronimo's avatar Michael Jeronimo Committed by Carl Delsey
Browse files

Integrate minor changes in nav2_bringup

parent 8eb19cad
No related branches found
No related tags found
No related merge requests found
<!--
This Behavior Tree first computes a path using the global planner (ComputePathToPose).
Then, it runs two sub-branches in parallel. The first sub-branch is a FollowPath
operation (the local planner). In parallel, there is a rate controlled execution of
FollowPath (the global planner). Each time a new path is computed, the path update
is sent to the local planner. The right branch, which is the rate controlled
ComputePathToPose, always returns RUNNING. Because the Parallel node uses a
threshold of 1, whenever the FollowPath returns SUCCESS or FAILURE, the parallel
node will return this result.
The goal (input to the global planner) and the resulting path (output of the global
planner and input to the local planner) are passed on the blackboard.
The rate at which the ComputePathToPose operation is invoked can be controlled with
the hz parameter to the RateController node.
-->
<root main_tree_to_execute="MainTree">
<BehaviorTree ID="MainTree">
<Sequence name="root">
......
......@@ -19,46 +19,63 @@ from ament_index_python.packages import get_package_share_directory
from launch.conditions import IfCondition
import launch.actions
import launch_ros.actions
def generate_launch_description():
# Get the launch directory
launch_dir = os.path.join(get_package_share_directory('nav2_bringup'), 'launch')
# Create the launch configuration variables
map_yaml_file = launch.substitutions.LaunchConfiguration('map')
use_sim_time = launch.substitutions.LaunchConfiguration('use_sim_time')
use_simulation = launch.substitutions.LaunchConfiguration('use_simulation')
simulator = launch.substitutions.LaunchConfiguration('simulator')
world = launch.substitutions.LaunchConfiguration('world')
params_file = launch.substitutions.LaunchConfiguration(
'params', default=[launch.substitutions.ThisLaunchFileDir(), '/nav2_params.yaml'])
params_file = launch.substitutions.LaunchConfiguration('params')
# Declare the launch arguments
declare_map_yaml_cmd = launch.actions.DeclareLaunchArgument(
'map',
default_value='test_map.yaml',
description='Full path to map file to load')
declare_use_sim_time_cmd = launch.actions.DeclareLaunchArgument(
'use_sim_time',
default_value='false',
description='Use simulation (Gazebo) clock if true')
declare_use_simulation_cmd = launch.actions.DeclareLaunchArgument(
'use_simulation', condition=IfCondition('True'),
default_value='True', description='Whether to run in simulation')
default_value='True',
description='Whether to run in simulation')
declare_simulator_cmd = launch.actions.DeclareLaunchArgument(
'simulator',
default_value='gzserver', description='The simulator to use (gazebo or gzserver)')
default_value='gzserver',
description='The simulator to use (gazebo or gzserver)')
declare_world_cmd = launch.actions.DeclareLaunchArgument(
'world',
default_value=os.path.join(
get_package_share_directory('turtlebot3_gazebo'),
'worlds/turtlebot3_worlds/burger.model'),
default_value=os.path.join(get_package_share_directory('turtlebot3_gazebo'), 'worlds/turtlebot3_worlds/burger.model'),
description='Full path to world file to load')
declare_params_file_cmd = launch.actions.DeclareLaunchArgument(
'params_file',
'params',
default_value='nav2_params.yaml',
description='Full path to the ROS2 parameters file to use for all launched nodes')
launch_dir = os.path.join(get_package_share_directory('nav2_bringup'), 'launch')
gz = launch.substitutions.LaunchConfiguration('gz', default=['gzserver'])
map_server_params = {
"yaml_filename" : "/home/mjeronimo/src/navigation2/nav2_bringup/launch/test_map.yaml"
}
# Specify the actions
start_gazebo_cmd = launch.actions.ExecuteProcess(
condition=IfCondition(use_simulation),
cmd=[simulator, '-s', 'libgazebo_ros_init.so', world, ['__params:=', params_file]],
cmd=[simulator, '-s', 'libgazebo_ros_init.so', world],
cwd=[launch_dir], output='screen')
start_robot_state_publisher_cmd = launch.actions.ExecuteProcess(
condition=IfCondition(use_simulation),
cmd=[
os.path.join(
get_package_prefix('robot_state_publisher'),
......@@ -126,30 +143,35 @@ def generate_launch_description():
['__params:=', params_file]],
cwd=[launch_dir], output='screen')
start_controller_cmd = launch.actions.ExecuteProcess(
start_lifecycle_manager_cmd = launch.actions.ExecuteProcess(
cmd=[
os.path.join(
get_package_prefix('nav2_controller'),
'lib/nav2_controller/nav2_controller'),
get_package_prefix('nav2_lifecycle_manager'),
'lib/nav2_lifecycle_manager/lifecycle_manager'),
['__params:=', params_file]],
cwd=[launch_dir], output='screen')
# Create the launch description and populate
ld = launch.LaunchDescription()
# First, declare the launch options
# Declare the launch options
ld.add_action(declare_map_yaml_cmd)
ld.add_action(declare_use_sim_time_cmd)
ld.add_action(declare_use_simulation_cmd)
ld.add_action(declare_simulator_cmd)
ld.add_action(declare_world_cmd)
ld.add_action(declare_params_file_cmd)
# Then, add the actions to launch the simulator-related nodes (conditioned on 'use_simulation')
# Add any actions to launch in simulation (conditioned on 'use_simulation')
ld.add_action(start_gazebo_cmd)
# Add other nodes and processes we need
ld.add_action(start_robot_state_publisher_cmd)
ld.add_action(start_rviz_cmd)
ld.add_action(exit_event_handler)
# Next, add the actions to launch all of the navigation nodes
ld.add_action(start_controller_cmd)
# Add the actions to launch all of the navigation nodes
ld.add_action(start_lifecycle_manager_cmd)
ld.add_action(start_map_server_cmd)
ld.add_action(start_localizer_cmd)
ld.add_action(start_world_model_cmd)
......
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment