Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

apply concatenate node update #62

Closed
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
97 changes: 76 additions & 21 deletions sample_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,28 +26,82 @@


def launch_setup(context, *args, **kwargs):
# set concat filter as a component
concat_component = ComposableNode(
package="pointcloud_preprocessor",
plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent",
name="concatenate_data",
remappings=[
("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"),
("output", "concatenated/pointcloud"),
],
parameters=[
{
"input_topics": [
"/sensing/lidar/top/outlier_filtered/pointcloud",
"/sensing/lidar/left/outlier_filtered/pointcloud",
"/sensing/lidar/right/outlier_filtered/pointcloud",
],
"output_frame": LaunchConfiguration("base_frame"),
}
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
# set concatenate filter as a component

separate_concatenate_node_and_timesync_node_str = LaunchConfiguration(
"separate_concatenate_node_and_timesync_node"
).perform(context)
separate_concatenate_node_and_timesync_node = (
separate_concatenate_node_and_timesync_node_str.lower() == "true"
)

# switch between sync_and_concatenate_filter and synchronizer_filter
if not separate_concatenate_node_and_timesync_node:
sync_and_concat_component = ComposableNode(
package="pointcloud_preprocessor",
plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent",
name="sync_and_concatenate_filter",
remappings=[
("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"),
("output", "concatenated/pointcloud"),
],
parameters=[
{
"input_topics": [
"/sensing/lidar/top/outlier_filtered/pointcloud",
"/sensing/lidar/left/outlier_filtered/pointcloud",
"/sensing/lidar/right/outlier_filtered/pointcloud",
],
"output_frame": LaunchConfiguration("base_frame"),
"approximate_sync": True,
"publish_synchronized_pointcloud": True, # set true if you want to publish synchronized pointcloud
}
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)
concat_components = [sync_and_concat_component]
else:
time_sync_component = ComposableNode(
package="pointcloud_preprocessor",
plugin="pointcloud_preprocessor::PointCloudDataSynchronizerComponent",
name="synchronizer_filter",
remappings=[
("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"),
],
parameters=[
{
"input_topics": [
"/sensing/lidar/top/outlier_filtered/pointcloud",
"/sensing/lidar/left/outlier_filtered/pointcloud",
"/sensing/lidar/right/outlier_filtered/pointcloud",
],
"output_frame": LaunchConfiguration("base_frame"),
"approximate_sync": True,
}
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)

concat_component = ComposableNode(
package="pointcloud_preprocessor",
plugin="pointcloud_preprocessor::PointCloudConcatenationComponent",
name="concatenate_filter",
remappings=[("output", "points_raw/concatenated")],
parameters=[
{
"input_topics": [
"/sensing/lidar/top/outlier_filtered/pointcloud_synchronized",
"/sensing/lidar/left/outlier_filtered/pointcloud_synchronized",
"/sensing/lidar/right/outlier_filtered/pointcloud_synchronized",
Comment on lines +93 to +95
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

/sensing/lidar/top/synchronized/pointcloud sounds better to me, like other nodes output

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If you want that, I need to update concatenate node file because its output topic names is created by adding "_synchronized" to the original message.

https://github.com/autowarefoundation/autoware.universe/pull/3312/files#diff-212becb09e27b26d36fa3eb6730c0100e20803559efd9e20e8901d2a57aceff0R64:~:text=%23define%20POSTFIX_NAME%20%22_synchronized%22

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ahh... I do want, but not urgent.
Defining like ~/synchronized/pointcloud in codes, and passing (or remapping) actual topic name from launcher is almost autoware coding manner.

],
"output_frame": LaunchConfiguration("base_frame"),
"approximate_sync": True,
}
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)
concat_components = [time_sync_component, concat_component]

# set container to run all required components in the same process
container = ComposableNodeContainer(
name=LaunchConfiguration("container_name"),
Expand All @@ -67,7 +121,7 @@ def launch_setup(context, *args, **kwargs):

# load concat or passthrough filter
concat_loader = LoadComposableNodes(
composable_node_descriptions=[concat_component],
composable_node_descriptions=concat_components,
target_container=target_container,
condition=IfCondition(LaunchConfiguration("use_concat_filter")),
)
Expand All @@ -86,6 +140,7 @@ def add_launch_arg(name: str, default_value=None):
add_launch_arg("use_intra_process", "False")
add_launch_arg("use_pointcloud_container", "False")
add_launch_arg("container_name", "pointcloud_preprocessor_container")
add_launch_arg("separate_concatenate_node_and_timesync_node", "False")

set_container_executable = SetLaunchConfiguration(
"container_executable",
Expand Down