Go2Py/deploy/launch_files/fast_lio.launch.py

48 lines
1.5 KiB
Python

import os.path
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
from launch.conditions import IfCondition
from launch_ros.actions import Node
def generate_launch_description():
package_path = get_package_share_directory('fast_lio')
default_config_path = os.path.join(package_path, 'config')
use_sim_time = LaunchConfiguration('use_sim_time')
config_path = LaunchConfiguration('config_path')
config_file = LaunchConfiguration('config_file')
declare_use_sim_time_cmd = DeclareLaunchArgument(
'use_sim_time', default_value='false',
description='Use simulation (Gazebo) clock if true'
)
declare_config_path_cmd = DeclareLaunchArgument(
'config_path', default_value=default_config_path,
description='Yaml config file path'
)
decalre_config_file_cmd = DeclareLaunchArgument(
'config_file', default_value='mid360.yaml',
description='Config file'
)
fast_lio_node = Node(
package='fast_lio',
executable='fastlio_mapping',
parameters=[PathJoinSubstitution([config_path, config_file]),
{'use_sim_time': use_sim_time}],
output='screen'
)
ld = LaunchDescription()
ld.add_action(declare_use_sim_time_cmd)
ld.add_action(declare_config_path_cmd)
ld.add_action(decalre_config_file_cmd)
ld.add_action(fast_lio_node)
return ld