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

feat(aip_x2_gen2_launch): update launch to run new concatenate node #386

Merged
merged 6 commits into from
Feb 5, 2025
Merged
Show file tree
Hide file tree
Changes from 2 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
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
/**:
Copy link
Contributor

@vividf vividf Feb 5, 2025

Choose a reason for hiding this comment

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

This parameter config might be wrong because these parameters are for x2 gen1.

Could you run the new algorithm with the parameters

/**:
  ros__parameters:
      debug_mode: false
      has_static_tf_only: false
      rosbag_length: 10.0
      maximum_queue_size: 5
      timeout_sec: 0.2
      is_motion_compensated: true
      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/left_lower/pointcloud_before_sync",
                    "/sensing/lidar/left_upper/pointcloud_before_sync",
                    "/sensing/lidar/front_lower/pointcloud_before_sync",
                    "/sensing/lidar/front_upper/pointcloud_before_sync",
                    "/sensing/lidar/right_upper/pointcloud_before_sync",
                    "/sensing/lidar/right_lower/pointcloud_before_sync",
                    "/sensing/lidar/rear_lower/pointcloud_before_sync",
                    "/sensing/lidar/rear_upper/pointcloud_before_sync"
                  ]
      output_frame: base_link
      matching_strategy:
        type: advanced
        lidar_timestamp_offsets: [0.0, 0.0, 0.025, 0.028, 0.026, 0.05, 0.075, 0.076]
        lidar_timestamp_noise_window: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01]

Copy link
Contributor

@vividf vividf Feb 5, 2025

Choose a reason for hiding this comment

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

Please help me verify that the time offsets between the LiDAR timestamps are accurate. (with ros2 topic echo pointcloud_topic --field header)
I set these parameters at the X2 Gen2 bench months ago, and I'm unsure if any sensor configurations have changed

Copy link
Contributor Author

Choose a reason for hiding this comment

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

@vividf
I played rosbag recorded on the x2 gen vehicle and did ros2 topic echo pointcloud_topic --field header.
Please tell me if you need any other information!

simplescreenrecorder-2025-02-05_14.37.34.mp4

Copy link
Contributor

@vividf vividf Feb 5, 2025

Choose a reason for hiding this comment

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

Thank you!
This helps a lot!

The parameters below should be accurate one

/**:
  ros__parameters:
      debug_mode: false
      has_static_tf_only: false
      rosbag_length: 10.0
      maximum_queue_size: 5
      timeout_sec: 0.2
      is_motion_compensated: true
      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/rear_upper/pointcloud_before_sync", # 0.047
                    "/sensing/lidar/rear_lower/pointcloud_before_sync", # 0.048
                    "/sensing/lidar/left_upper/pointcloud_before_sync", # 0.048
                    "/sensing/lidar/left_lower/pointcloud_before_sync", # 0.047
                    "/sensing/lidar/front_upper/pointcloud_before_sync", # 0.072
                    "/sensing/lidar/front_lower/pointcloud_before_sync", # 0.072
                    "/sensing/lidar/right_upper/pointcloud_before_sync", # 0.073
                    "/sensing/lidar/right_lower/pointcloud_before_sync" # 0.097
                  ]
      output_frame: base_link
      matching_strategy:
        type: advanced
        lidar_timestamp_offsets: [0.0, 0.001, 0.001, 0.0, 0.025, 0.025, 0.026, 0.050]
        lidar_timestamp_noise_window: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01]

Copy link
Contributor

@vividf vividf Feb 5, 2025

Choose a reason for hiding this comment

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

@TomohitoAndo Sorry! I set two values wrong.
0.01 -> 0.001

Copy link
Contributor

Choose a reason for hiding this comment

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

lidar_timestamp_offsets: [0.0, 0.001, 0.001, 0.0, 0.025, 0.025, 0.026, 0.050]

Copy link
Contributor Author

@TomohitoAndo TomohitoAndo Feb 5, 2025

Choose a reason for hiding this comment

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

Thank you!
updated param in fcb43fd

I confirmed diagnostics was OK with logging_simulator 😄
image
image

Copy link
Contributor

Choose a reason for hiding this comment

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

I updated the parameters by myself
#386 (comment)

ros__parameters:
debug_mode: false
has_static_tf_only: false
rosbag_length: 10.0
maximum_queue_size: 5
timeout_sec: 0.2
is_motion_compensated: true
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/rear_upper/pointcloud_before_sync", # 0.044
"/sensing/lidar/rear_lower/pointcloud_before_sync", # 0.049
"/sensing/lidar/left_upper/pointcloud_before_sync", # 0.05
"/sensing/lidar/left_lower/pointcloud_before_sync", # 0.05
"/sensing/lidar/front_upper/pointcloud_before_sync", # 0.075
"/sensing/lidar/front_lower/pointcloud_before_sync", # 0.074
"/sensing/lidar/right_upper/pointcloud_before_sync", # 0.090
"/sensing/lidar/right_lower/pointcloud_before_sync", # 0.00
]
output_frame: base_link
matching_strategy:
type: advanced
lidar_timestamp_offsets: [0.0, 0.005, 0.006, 0.006, 0.031, 0.03, 0.046, 0.056]
lidar_timestamp_noise_window: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01]
4 changes: 2 additions & 2 deletions aip_x2_gen2_launch/launch/nebula_node_container.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -180,7 +180,7 @@ def str2vector(string):
name="ring_outlier_filter",
remappings=[
("input", "rectified/pointcloud_ex"),
("output", "pointcloud"),
("output", "pointcloud_before_sync"),
],
parameters=[ring_outlier_filter_node_param, ring_outlier_output_frame],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
Expand All @@ -192,7 +192,7 @@ def str2vector(string):
name="dual_return_filter",
remappings=[
("input", "rectified/pointcloud_ex"),
("output", "pointcloud"),
("output", "pointcloud_before_sync"),
],
parameters=[
{
Expand Down
43 changes: 24 additions & 19 deletions aip_x2_gen2_launch/launch/pointcloud_preprocessor.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -22,9 +24,18 @@
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",
Expand All @@ -34,30 +45,15 @@ def launch_setup(context, *args, **kwargs):
("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"),
("output", "concatenated/pointcloud"),
],
parameters=[
{
"input_topics": [
"/sensing/lidar/front_upper/pointcloud",
"/sensing/lidar/front_lower/pointcloud",
"/sensing/lidar/left_upper/pointcloud",
"/sensing/lidar/left_lower/pointcloud",
"/sensing/lidar/right_upper/pointcloud",
"/sensing/lidar/right_lower/pointcloud",
"/sensing/lidar/rear_upper/pointcloud",
"/sensing/lidar/rear_lower/pointcloud",
],
"input_offset": [0.005, 0.025, 0.050, 0.005, 0.050, 0.005, 0.005, 0.025],
"timeout_sec": 0.075,
"output_frame": LaunchConfiguration("base_frame"),
"input_twist_topic_type": "twist",
}
],
parameters=[concatenate_and_time_sync_node_param],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)

# load concat or passthrough filter
concat_loader = LoadComposableNodes(
composable_node_descriptions=[concat_component],
target_container=LaunchConfiguration("pointcloud_container_name"),
condition=IfCondition(LaunchConfiguration("use_concat_filter")),
)

return [concat_loader]
Expand All @@ -69,10 +65,19 @@ def generate_launch_description():
def add_launch_arg(name: str, default_value=None):
launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value))

add_launch_arg("base_frame", "base_link")
aip_x2_gen2_launch_share_dir = get_package_share_directory("aip_x2_gen2_launch")

add_launch_arg("use_multithread", "True")
add_launch_arg("use_intra_process", "True")
add_launch_arg("pointcloud_container_name", "pointcloud_container")
add_launch_arg(
"concatenate_and_time_sync_node_param_path",
os.path.join(
aip_x2_gen2_launch_share_dir,
"config",
"concatenate_and_time_sync_node.param.yaml",
),
)

set_container_executable = SetLaunchConfiguration(
"container_executable",
Expand Down
Loading