slam.launch.py 1.7 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647
  1. # Copyright (c) Contributors to the Open 3D Engine Project.
  2. #
  3. # Licensed under the Apache License, Version 2.0 (the "License");
  4. # you may not use this file except in compliance with the License.
  5. # You may obtain a copy of the License at
  6. #
  7. # http://www.apache.org/licenses/LICENSE-2.0
  8. #
  9. # Unless required by applicable law or agreed to in writing, software
  10. # distributed under the License is distributed on an "AS IS" BASIS,
  11. # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  12. # See the License for the specific language governing permissions and
  13. # limitations under the License.
  14. import pathlib
  15. from ament_index_python.packages import get_package_share_directory
  16. from launch import LaunchDescription
  17. from launch.actions import IncludeLaunchDescription
  18. from launch.launch_description_sources import PythonLaunchDescriptionSource
  19. from launch_ros.actions import Node
  20. def generate_launch_description():
  21. return LaunchDescription([
  22. IncludeLaunchDescription(
  23. PythonLaunchDescriptionSource([str(pathlib.Path(
  24. get_package_share_directory('slam_toolbox')).joinpath('launch', 'online_async_launch.py'))]),
  25. launch_arguments = {
  26. 'slam_params_file': str(pathlib.Path(__file__).parent.absolute().joinpath('config', 'slam_params.yaml'))
  27. }.items()
  28. ),
  29. Node(
  30. package='pointcloud_to_laserscan',
  31. executable='pointcloud_to_laserscan_node',
  32. name='pc_to_laserscan',
  33. parameters=[{
  34. 'min_height': 0.0,
  35. 'max_height': 0.4,
  36. 'range_min': 0.05
  37. }],
  38. remappings=[
  39. ('/cloud_in', '/pc'),
  40. ]
  41. )
  42. ])