Files
ros-raspbot-v2/lidar/sllidar_ros2/launch/sllidar_t1_launch.py
T

73 lines
2.5 KiB
Python

#!/usr/bin/env python3
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.actions import LogInfo
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
def generate_launch_description():
channel_type = LaunchConfiguration('channel_type', default='udp')
udp_ip = LaunchConfiguration('udp_ip', default='192.168.11.2')
udp_port = LaunchConfiguration('udp_port', default='8089')
frame_id = LaunchConfiguration('frame_id', default='laser')
inverted = LaunchConfiguration('inverted', default='false')
angle_compensate = LaunchConfiguration('angle_compensate', default='true')
scan_mode = LaunchConfiguration('scan_mode', default='Sensitivity')
return LaunchDescription([
DeclareLaunchArgument(
'channel_type',
default_value=channel_type,
description='Specifying channel type of lidar'),
DeclareLaunchArgument(
'udp_ip',
default_value=udp_ip,
description='Specifying udp ip to connected lidar'),
DeclareLaunchArgument(
'udp_port',
default_value=udp_port,
description='Specifying udp port to connected lidar'),
DeclareLaunchArgument(
'frame_id',
default_value=frame_id,
description='Specifying frame_id of lidar'),
DeclareLaunchArgument(
'inverted',
default_value=inverted,
description='Specifying whether or not to invert scan data'),
DeclareLaunchArgument(
'angle_compensate',
default_value=angle_compensate,
description='Specifying whether or not to enable angle_compensate of scan data'),
DeclareLaunchArgument(
'scan_mode',
default_value=scan_mode,
description='Specifying scan mode of lidar'),
Node(
package='sllidar_ros2',
executable='sllidar_node',
name='sllidar_node',
parameters=[{'channel_type': channel_type,
'udp_ip': udp_ip,
'udp_port': udp_port,
'frame_id': frame_id,
'inverted': inverted,
'angle_compensate': angle_compensate,
'scan_mode': scan_mode}],
output='screen'),
])