diff --git a/awsim_sensor_kit_launch/config/concatenate_and_time_sync_node.param.yaml b/awsim_sensor_kit_launch/config/concatenate_and_time_sync_node.param.yaml new file mode 100644 index 0000000..bb527cd --- /dev/null +++ b/awsim_sensor_kit_launch/config/concatenate_and_time_sync_node.param.yaml @@ -0,0 +1,21 @@ +/**: + ros__parameters: + debug_mode: false + has_static_tf_only: false + rosbag_length: 10.0 + maximum_queue_size: 5 + timeout_sec: 0.01 + is_motion_compensated: false + publish_synchronized_pointcloud: true + keep_input_frame_in_synchronized_pointcloud: true + publish_previous_but_late_pointcloud: false + synchronized_pointcloud_postfix: pointcloud + input_twist_topic_type: twist + input_topics: [ + "/sensing/lidar/right/pointcloud_before_sync", # Fill this after using the right point cloud + "/sensing/lidar/top/pointcloud_before_sync", # 0.05 + "/sensing/lidar/left/pointcloud_before_sync", # Fill this after using the left point cloud + ] + output_frame: base_link + lidar_timestamp_offsets: [0.0, 0.0, 0.0] + lidar_timestamp_noise_window: [0.01, 0.01, 0.01] diff --git a/awsim_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py b/awsim_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py index 6bfec90..bbabebf 100644 --- a/awsim_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py +++ b/awsim_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py @@ -12,7 +12,9 @@ # See the License for the specific language governing permissions and # limitations under the License. +import os +from ament_index_python.packages import get_package_share_directory import launch from launch.actions import DeclareLaunchArgument from launch.actions import OpaqueFunction @@ -22,9 +24,16 @@ from launch.substitutions import LaunchConfiguration from launch_ros.actions import LoadComposableNodes from launch_ros.descriptions import ComposableNode - +from launch_ros.parameter_descriptions import ParameterFile def launch_setup(context, *args, **kwargs): + # concatenate node parameters + concatenate_and_time_sync_node_param = ParameterFile( + param_file=LaunchConfiguration("concatenate_and_time_sync_node_param_path").perform( + context + ), + allow_substs=True, + ) # set concat filter as a component concat_component = ComposableNode( package="autoware_pointcloud_preprocessor", @@ -37,19 +46,7 @@ def launch_setup(context, *args, **kwargs): ), ("output", "concatenated/pointcloud"), ], - parameters=[ - { - "input_topics": [ - "/sensing/lidar/top/pointcloud_before_sync", - "/sensing/lidar/left/pointcloud_before_sync", - "/sensing/lidar/right/pointcloud_before_sync", - ], - "output_frame": LaunchConfiguration("base_frame"), - "input_twist_topic_type": "twist", - "publish_synchronized_pointcloud": True, - "timeout_sec": 0.01, - } - ], + parameters=[concatenate_and_time_sync_node_param], extra_arguments=[ {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} ], @@ -73,10 +70,18 @@ def add_launch_arg(name: str, default_value=None): DeclareLaunchArgument(name, default_value=default_value) ) - add_launch_arg("base_frame", "base_link") + awsim_sensor_kit_launch_share_dir = get_package_share_directory("awsim_sensor_kit_launch") add_launch_arg("use_multithread", "False") add_launch_arg("use_intra_process", "False") add_launch_arg("pointcloud_container_name", "pointcloud_container") + add_launch_arg( + "concatenate_and_time_sync_node_param_path", + os.path.join( + awsim_sensor_kit_launch_share_dir, + "config", + "concatenate_and_time_sync_node.param.yaml", + ), + ) set_container_executable = SetLaunchConfiguration( "container_executable",