wip-behaviors #3

Merged
Pimpest merged 86 commits from wip-behaviors into main 2026-05-28 06:21:26 +00:00
Showing only changes of commit f84ca5d3bf - Show all commits

View File

@@ -7,6 +7,7 @@ from launch_ros.substitutions import FindPackageShare
from pathlib import Path
def generate_launch_description():
basedir = FindPackageShare("").find("toid_lidar")
@@ -19,50 +20,48 @@ def generate_launch_description():
use_closest = LaunchConfiguration("use_closest")
lidar_frame = LaunchConfiguration("lidar_frame")
return LaunchDescription([
DeclareLaunchArgument(
'visualize',
default_value='False',
description="Whether to launch rviz2"
),
DeclareLaunchArgument(
'draw_markers',
default_value='False',
description="Draw markers"
),
DeclareLaunchArgument(
'use_closest',
default_value='True',
description="Use closest point for calibration"
),
DeclareLaunchArgument(
'lidar_frame',
default_value='lidar_frame',
description="TF frame of the lidar"
),
Node(
package='toid_lidar',
executable='toid_lidar',
output="screen",
parameters=[
lidar_config,
{
'closest': use_closest,
'draw_markers': draw_markers
}]
),
Node(
package='rplidar_ros',
executable='rplidar_composition',
output="screen",
parameters=[lidar_config, {'frame_id': lidar_frame}]
),
Node(
package='rviz2',
executable='rviz2',
name='rviz2',
output='screen',
arguments=['-d', rviz_config],
condition=IfCondition(visualize)
)
])
return LaunchDescription(
[
DeclareLaunchArgument(
"visualize",
default_value="False",
description="Whether to launch rviz2",
),
DeclareLaunchArgument(
"draw_markers", default_value="False", description="Draw markers"
),
DeclareLaunchArgument(
"use_closest",
default_value="True",
description="Use closest point for calibration",
),
DeclareLaunchArgument(
"lidar_frame",
default_value="lidar_frame",
description="TF frame of the lidar",
),
Node(
package="toid_lidar",
executable="toid_lidar",
output="screen",
parameters=[
lidar_config,
{"closest": use_closest, "draw_markers": draw_markers},
],
),
Node(
package="rplidar_ros",
executable="rplidar_composition",
output="screen",
parameters=[lidar_config, {"frame_id": lidar_frame}],
),
Node(
package="rviz2",
executable="rviz2",
name="rviz2",
output="screen",
arguments=["-d", rviz_config],
condition=IfCondition(visualize),
),
]
)