ROS2-SLAM-Fundamental/map_merge/launch/tb3_simulation/slam_toolbox.py
Carlos Andrés Álvarez Restrepo f808bc404a
PORT: multirobot_map_merge (#8)
* Baby steps

* Compile without implementations

* Compile combined_grids

* Compile part of principal node map_merge.cpp

* Finish 90% of main node

* Move ros::names implementation to own file

* Replace ros1 while loops threads with ros2 timers

* Fix checking of map type for adding robots. bypass mutex for now

* Working version without init poses, still verbose logs

* Add namespace to explore_lite
Add tb3 launch files for multirobot tests
Finish multirobot map merge with poses known

* Add files for tb3 demo

* Fix launch file for demo with robot poses

* Fix comments on locking

* Change deprecated Ptr to SharedPtr in ros2 msgs variables

* Change ConstPtr to ConstSharedPtr for ROS2

* Fix minor warnings in explor_lite

* Attempt fix slam toolbox

* Add launch and remove old ones

* Add copyright

* Add readme with instruction on how to run the demo in sim

* Fix readme and port from_map_server launch file

* Fix QoS for suscriptions with TRansientlocal
2021-12-26 20:28:18 -05:00

50 lines
1.5 KiB
Python

import os
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
from ament_index_python.packages import get_package_share_directory
def generate_launch_description():
use_sim_time = LaunchConfiguration("use_sim_time")
slam_params_file = LaunchConfiguration("slam_params_file")
remappings = [
("/map", "map"),
("/scan", "scan"),
("/tf", "tf"),
("/tf_static", "tf_static"),
]
declare_use_sim_time_argument = DeclareLaunchArgument(
"use_sim_time", default_value="true", description="Use simulation/Gazebo clock"
)
declare_slam_params_file_cmd = DeclareLaunchArgument(
"slam_params_file",
default_value=os.path.join(
get_package_share_directory("slam_toolbox"),
"config",
"mapper_params_online_sync.yaml",
),
description="Full path to the ROS2 parameters file to use for the slam_toolbox node",
)
start_sync_slam_toolbox_node = Node(
parameters=[slam_params_file, {"use_sim_time": use_sim_time}],
package="slam_toolbox",
executable="sync_slam_toolbox_node",
name="slam_toolbox",
output="screen",
remappings=remappings,
)
ld = LaunchDescription()
ld.add_action(declare_use_sim_time_argument)
ld.add_action(declare_slam_params_file_cmd)
ld.add_action(start_sync_slam_toolbox_node)
return ld