Support ros2 Humble.
This commit is contained in:
68
launch/mapping_avia.launch.py
Normal file
68
launch/mapping_avia.launch.py
Normal file
@@ -0,0 +1,68 @@
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import GroupAction, DeclareLaunchArgument
|
||||
from launch.conditions import IfCondition
|
||||
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
|
||||
from launch_ros.actions import Node
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
# Declare the RViz argument
|
||||
rviz_arg = DeclareLaunchArgument(
|
||||
'rviz', default_value='true',
|
||||
description='Flag to launch RViz.')
|
||||
|
||||
# Node parameters, including those from the YAML configuration file
|
||||
laser_mapping_params = [
|
||||
PathJoinSubstitution([
|
||||
FindPackageShare('point_lio'),
|
||||
'config', 'avia.yaml'
|
||||
]),
|
||||
{
|
||||
'use_imu_as_input': False, # Change to True to use IMU as input of Point-LIO
|
||||
'prop_at_freq_of_imu': True,
|
||||
'check_satu': True,
|
||||
'init_map_size': 10,
|
||||
'point_filter_num': 1, # options: 4, 3
|
||||
'space_down_sample': True,
|
||||
'filter_size_surf': 0.3, # options: 0.5, 0.3, 0.2, 0.15, 0.1
|
||||
'filter_size_map': 0.2, # options: 0.5, 0.3, 0.15, 0.1
|
||||
'cube_side_length': 2000.0, # option: 1000
|
||||
'runtime_pos_log_enable': False, # option: True
|
||||
},
|
||||
]
|
||||
|
||||
# Node definition for laserMapping with Point-LIO
|
||||
laser_mapping_node = Node(
|
||||
package='point_lio',
|
||||
executable='pointlio_mapping',
|
||||
name='laserMapping',
|
||||
output='screen',
|
||||
parameters=laser_mapping_params,
|
||||
# prefix='gdb -ex run --args'
|
||||
)
|
||||
|
||||
# Conditional RViz node launch
|
||||
rviz_node = Node(
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
name='rviz',
|
||||
arguments=['-d', PathJoinSubstitution([
|
||||
FindPackageShare('point_lio'),
|
||||
'rviz_cfg', 'loam_livox.rviz'
|
||||
])],
|
||||
condition=IfCondition(LaunchConfiguration('rviz')),
|
||||
prefix='nice'
|
||||
)
|
||||
|
||||
# Assemble the launch description
|
||||
ld = LaunchDescription([
|
||||
rviz_arg,
|
||||
laser_mapping_node,
|
||||
GroupAction(
|
||||
actions=[rviz_node],
|
||||
condition=IfCondition(LaunchConfiguration('rviz'))
|
||||
),
|
||||
])
|
||||
|
||||
return ld
|
||||
68
launch/mapping_horizon.launch.py
Normal file
68
launch/mapping_horizon.launch.py
Normal file
@@ -0,0 +1,68 @@
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import GroupAction, DeclareLaunchArgument
|
||||
from launch.conditions import IfCondition
|
||||
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
|
||||
from launch_ros.actions import Node
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
# Declare the RViz argument
|
||||
rviz_arg = DeclareLaunchArgument(
|
||||
'rviz', default_value='true',
|
||||
description='Flag to launch RViz.')
|
||||
|
||||
# Node parameters, including those from the YAML configuration file
|
||||
laser_mapping_params = [
|
||||
PathJoinSubstitution([
|
||||
FindPackageShare('point_lio'),
|
||||
'config', 'horizon.yaml'
|
||||
]),
|
||||
{
|
||||
'use_imu_as_input': False, # Change to True to use IMU as input of Point-LIO
|
||||
'prop_at_freq_of_imu': True,
|
||||
'check_satu': True,
|
||||
'init_map_size': 10,
|
||||
'point_filter_num': 3, # Options: 1, 3
|
||||
'space_down_sample': True,
|
||||
'filter_size_surf': 0.5, # Options: 0.5, 0.3, 0.2, 0.15, 0.1
|
||||
'filter_size_map': 0.5, # Options: 0.5, 0.3, 0.15, 0.1
|
||||
'cube_side_length': 1000.0, # Option: 1000
|
||||
'runtime_pos_log_enable': False, # Option: True
|
||||
}
|
||||
]
|
||||
|
||||
# Node definition for laserMapping with Point-LIO
|
||||
laser_mapping_node = Node(
|
||||
package='point_lio',
|
||||
executable='pointlio_mapping',
|
||||
name='laserMapping',
|
||||
output='screen',
|
||||
parameters=laser_mapping_params,
|
||||
# prefix='gdb -ex run --args'
|
||||
)
|
||||
|
||||
# Conditional RViz node launch
|
||||
rviz_node = Node(
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
name='rviz',
|
||||
arguments=['-d', PathJoinSubstitution([
|
||||
FindPackageShare('point_lio'),
|
||||
'rviz_cfg', 'loam_livox.rviz'
|
||||
])],
|
||||
condition=IfCondition(LaunchConfiguration('rviz')),
|
||||
prefix='nice'
|
||||
)
|
||||
|
||||
# Assemble the launch description
|
||||
ld = LaunchDescription([
|
||||
rviz_arg,
|
||||
laser_mapping_node,
|
||||
GroupAction(
|
||||
actions=[rviz_node],
|
||||
condition=IfCondition(LaunchConfiguration('rviz'))
|
||||
),
|
||||
])
|
||||
|
||||
return ld
|
||||
57
launch/mapping_mid360.launch.py
Normal file
57
launch/mapping_mid360.launch.py
Normal file
@@ -0,0 +1,57 @@
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import GroupAction, DeclareLaunchArgument
|
||||
from launch.conditions import IfCondition
|
||||
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
|
||||
from launch_ros.actions import Node
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
# Declare the RViz argument
|
||||
rviz_arg = DeclareLaunchArgument(
|
||||
'rviz', default_value='true',
|
||||
description='Flag to launch RViz.')
|
||||
|
||||
# Node parameters, including those from the YAML configuration file
|
||||
laser_mapping_params = [
|
||||
PathJoinSubstitution([
|
||||
FindPackageShare('point_lio'),
|
||||
'config', 'mid360.yaml'
|
||||
])
|
||||
]
|
||||
|
||||
# Node definition for laserMapping with Point-LIO
|
||||
laser_mapping_node = Node(
|
||||
package='point_lio',
|
||||
executable='pointlio_mapping',
|
||||
name='laserMapping',
|
||||
output='screen',
|
||||
parameters=laser_mapping_params,
|
||||
# prefix='gdb -ex run --args'
|
||||
)
|
||||
|
||||
# Conditional RViz node launch
|
||||
rviz_node = Node(
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
name='rviz',
|
||||
arguments=['-d', PathJoinSubstitution([
|
||||
FindPackageShare('point_lio'),
|
||||
'rviz_cfg', 'loam_livox.rviz'
|
||||
])],
|
||||
condition=IfCondition(LaunchConfiguration('rviz')),
|
||||
prefix='nice'
|
||||
)
|
||||
|
||||
# Assemble the launch description
|
||||
ld = LaunchDescription([
|
||||
rviz_arg,
|
||||
laser_mapping_node,
|
||||
#octomap_server_node,
|
||||
GroupAction(
|
||||
actions=[rviz_node],
|
||||
condition=IfCondition(LaunchConfiguration('rviz'))
|
||||
),
|
||||
])
|
||||
|
||||
return ld
|
||||
68
launch/mapping_ouster64.launch.py
Normal file
68
launch/mapping_ouster64.launch.py
Normal file
@@ -0,0 +1,68 @@
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import GroupAction, DeclareLaunchArgument
|
||||
from launch.conditions import IfCondition
|
||||
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
|
||||
from launch_ros.actions import Node
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
# Declare the RViz argument
|
||||
rviz_arg = DeclareLaunchArgument(
|
||||
'rviz', default_value='true',
|
||||
description='Flag to launch RViz.')
|
||||
|
||||
# Node parameters, including those from the YAML configuration file
|
||||
laser_mapping_params = [
|
||||
PathJoinSubstitution([
|
||||
FindPackageShare('point_lio'),
|
||||
'config', 'ouster64.yaml'
|
||||
]),
|
||||
{
|
||||
'use_imu_as_input': False, # Change to True to use IMU as input of Point-LIO
|
||||
'prop_at_freq_of_imu': True,
|
||||
'check_satu': True,
|
||||
'init_map_size': 10,
|
||||
'point_filter_num': 4, # Options: 4, 3
|
||||
'space_down_sample': True,
|
||||
'filter_size_surf': 0.5, # Options: 0.5, 0.3, 0.2, 0.15, 0.1
|
||||
'filter_size_map': 0.5, # Options: 0.5, 0.3, 0.15, 0.1
|
||||
'cube_side_length': 1000.0, # Option: 1000 (changed from 2000)
|
||||
'runtime_pos_log_enable': False, # Option: True
|
||||
}
|
||||
]
|
||||
|
||||
# Node definition for laserMapping with Point-LIO
|
||||
laser_mapping_node = Node(
|
||||
package='point_lio',
|
||||
executable='pointlio_mapping',
|
||||
name='laserMapping',
|
||||
output='screen',
|
||||
parameters=laser_mapping_params,
|
||||
# prefix='gdb -ex run --args'
|
||||
)
|
||||
|
||||
# Conditional RViz node launch
|
||||
rviz_node = Node(
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
name='rviz',
|
||||
arguments=['-d', PathJoinSubstitution([
|
||||
FindPackageShare('point_lio'),
|
||||
'rviz_cfg', 'loam_livox.rviz'
|
||||
])],
|
||||
condition=IfCondition(LaunchConfiguration('rviz')),
|
||||
prefix='nice'
|
||||
)
|
||||
|
||||
# Assemble the launch description
|
||||
ld = LaunchDescription([
|
||||
rviz_arg,
|
||||
laser_mapping_node,
|
||||
GroupAction(
|
||||
actions=[rviz_node],
|
||||
condition=IfCondition(LaunchConfiguration('rviz'))
|
||||
),
|
||||
])
|
||||
|
||||
return ld
|
||||
68
launch/mapping_velody16.launch.py
Normal file
68
launch/mapping_velody16.launch.py
Normal file
@@ -0,0 +1,68 @@
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import GroupAction, DeclareLaunchArgument
|
||||
from launch.conditions import IfCondition
|
||||
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
|
||||
from launch_ros.actions import Node
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
# Declare the RViz argument
|
||||
rviz_arg = DeclareLaunchArgument(
|
||||
'rviz', default_value='true',
|
||||
description='Flag to launch RViz.')
|
||||
|
||||
# Node parameters, including those from the YAML configuration file
|
||||
laser_mapping_params = [
|
||||
PathJoinSubstitution([
|
||||
FindPackageShare('point_lio'),
|
||||
'config', 'velody16.yaml'
|
||||
]),
|
||||
{
|
||||
'use_imu_as_input': False, # Change to True to use IMU as input of Point-LIO
|
||||
'prop_at_freq_of_imu': True,
|
||||
'check_satu': True,
|
||||
'init_map_size': 10,
|
||||
'point_filter_num': 4, # Options: 4, 3
|
||||
'space_down_sample': True,
|
||||
'filter_size_surf': 0.5, # Options: 0.5, 0.3, 0.2, 0.15, 0.1
|
||||
'filter_size_map': 0.5, # Options: 0.5, 0.3, 0.15, 0.1
|
||||
'cube_side_length': 1000.0, # Option: 1000 (changed from 2000)
|
||||
'runtime_pos_log_enable': False, # Option: True
|
||||
}
|
||||
]
|
||||
|
||||
# Node definition for laserMapping with Point-LIO
|
||||
laser_mapping_node = Node(
|
||||
package='point_lio',
|
||||
executable='pointlio_mapping',
|
||||
name='laserMapping',
|
||||
output='screen',
|
||||
parameters=laser_mapping_params,
|
||||
# prefix='gdb -ex run --args'
|
||||
)
|
||||
|
||||
# Conditional RViz node launch
|
||||
rviz_node = Node(
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
name='rviz',
|
||||
arguments=['-d', PathJoinSubstitution([
|
||||
FindPackageShare('point_lio'),
|
||||
'rviz_cfg', 'loam_livox.rviz'
|
||||
])],
|
||||
condition=IfCondition(LaunchConfiguration('rviz')),
|
||||
prefix='nice'
|
||||
)
|
||||
|
||||
# Assemble the launch description
|
||||
ld = LaunchDescription([
|
||||
rviz_arg,
|
||||
laser_mapping_node,
|
||||
GroupAction(
|
||||
actions=[rviz_node],
|
||||
condition=IfCondition(LaunchConfiguration('rviz'))
|
||||
),
|
||||
])
|
||||
|
||||
return ld
|
||||
Reference in New Issue
Block a user