Skip to content

Commit

Permalink
feat: initialize parameters for concatenate
Browse files Browse the repository at this point in the history
Signed-off-by: vividf <[email protected]>
  • Loading branch information
vividf committed Oct 30, 2024
1 parent 03de6c2 commit b0c157b
Show file tree
Hide file tree
Showing 8 changed files with 182 additions and 79 deletions.
21 changes: 21 additions & 0 deletions aip_x1_launch/config/concatenate_and_time_sync_node.param.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
/**:
ros__parameters:
debug_mode: false
has_static_tf_only: false
rosbag_replay: false
rosbag_length: 20.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/top/pointcloud_before_sync", # unknown timestamp
"/sensing/lidar/front_center/pointcloud_before_sync", # unknown timestamp
]
output_frame: base_link
lidar_timestamp_offsets: [0.0, 0.02] # unknown offset
lidar_timestamp_noise_window: [0.01, 0.01]
39 changes: 22 additions & 17 deletions aip_x1_launch/launch/pointcloud_preprocessor.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +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 @@ -21,9 +24,17 @@
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 @@ -33,22 +44,7 @@ def launch_setup(context, *args, **kwargs):
("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"),
("output", "concatenated/pointcloud"),
],
parameters=[
{
"input_topics": [
"/sensing/lidar/top/pointcloud_before_sync",
"/sensing/lidar/front_center/pointcloud_before_sync",
],
"output_frame": LaunchConfiguration("base_frame"),
"input_offset": [
0.055,
0.025,
],
"timeout_sec": 0.095,
"input_twist_topic_type": "twist",
"publish_synchronized_pointcloud": True,
}
],
parameters=[concatenate_and_time_sync_node_param],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)

Expand All @@ -68,10 +64,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_x1_launch_share_dir = get_package_share_directory("aip_x1_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(
aip_x1_launch_share_dir,
"config",
"concatenate_and_time_sync_node.param.yaml",
),
)

set_container_executable = SetLaunchConfiguration(
"container_executable",
Expand Down
27 changes: 27 additions & 0 deletions aip_x2_launch/config/concatenate_and_time_sync_node.param.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
/**:
ros__parameters:
debug_mode: false
has_static_tf_only: false
rosbag_replay: false
rosbag_length: 20.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_upper/pointcloud_before_sync", # 0.05
"/sensing/lidar/left_lower/pointcloud_before_sync", # 0.05
"/sensing/lidar/front_upper/pointcloud_before_sync", # 0.025
"/sensing/lidar/front_lower/pointcloud_before_sync", # 0.074
"/sensing/lidar/right_upper/pointcloud_before_sync", # 0.091
"/sensing/lidar/right_lower/pointcloud_before_sync", # 0.00
"/sensing/lidar/rear_upper/pointcloud_before_sync", # 0.055
"/sensing/lidar/rear_lower/pointcloud_before_sync", # 0.065
]
output_frame: base_link
lidar_timestamp_offsets: [0.0, 0.0, 0.075, 0.024, 0.041, 0.05, 0.005, 0.015]
lidar_timestamp_noise_window: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01]
43 changes: 23 additions & 20 deletions aip_x2_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,25 +45,7 @@ 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_before_sync",
"/sensing/lidar/front_lower/pointcloud_before_sync",
"/sensing/lidar/left_upper/pointcloud_before_sync",
"/sensing/lidar/left_lower/pointcloud_before_sync",
"/sensing/lidar/right_upper/pointcloud_before_sync",
"/sensing/lidar/right_lower/pointcloud_before_sync",
"/sensing/lidar/rear_upper/pointcloud_before_sync",
"/sensing/lidar/rear_lower/pointcloud_before_sync",
],
"input_offset": [0.025, 0.025, 0.01, 0.0, 0.05, 0.05, 0.05, 0.05],
"timeout_sec": 0.075,
"output_frame": LaunchConfiguration("base_frame"),
"input_twist_topic_type": "twist",
"publish_synchronized_pointcloud": True,
}
],
parameters=[concatenate_and_time_sync_node_param],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)

Expand All @@ -72,11 +65,21 @@ 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_launch_share_dir = get_package_share_directory("aip_x2_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_launch_share_dir,
"config",
"concatenate_and_time_sync_node.param.yaml",
),
)

set_container_executable = SetLaunchConfiguration(
"container_executable",
"component_container",
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
/**:
ros__parameters:
debug_mode: false
has_static_tf_only: false
rosbag_replay: false
rosbag_length: 20.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/top/pointcloud", # unknown timestamp
"/sensing/lidar/left/pointcloud", # unknown timestamp
"/sensing/lidar/right/pointcloud", # unknown timestamp
"/sensing/lidar/rear/pointcloud", # unknown timestamp
]
output_frame: base_link
lidar_timestamp_offsets: [0.0, 0.02, 0.02, 0.02] # unknown offset
lidar_timestamp_noise_window: [0.01, 0.01, 0.01, 0.01]
42 changes: 21 additions & 21 deletions aip_xx1_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,20 +45,7 @@ def launch_setup(context, *args, **kwargs):
("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"),
("output", "concatenated/pointcloud"),
],
parameters=[
{
"input_topics": LaunchConfiguration("input_topics"),
"output_frame": LaunchConfiguration("base_frame"),
"input_offset": LaunchConfiguration(
"input_offset"
), # each sensor will wait 60, 70, 70, 70ms
"timeout_sec": LaunchConfiguration("timeout_sec"), # set shorter than 100ms
"input_twist_topic_type": LaunchConfiguration("input_twist_topic_type"),
"publish_synchronized_pointcloud": LaunchConfiguration(
"publish_synchronized_pointcloud"
),
}
],
parameters=[concatenate_and_time_sync_node_param],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)

Expand All @@ -67,19 +65,21 @@ 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_xx1_gen2_launch_share_dir = get_package_share_directory("aip_xx1_gen2_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("individual_container_name", "concatenate_container")

add_launch_arg(
"input_topics",
"[/sensing/lidar/top/pointcloud, /sensing/lidar/left/pointcloud, /sensing/lidar/right/pointcloud, /sensing/lidar/rear/pointcloud]",
"concatenate_and_time_sync_node_param_path",
os.path.join(
aip_xx1_gen2_launch_share_dir,
"config",
"concatenate_and_time_sync_node.param.yaml",
),
)
add_launch_arg("input_offset", "[0.035, 0.025, 0.025, 0.025]")
add_launch_arg("timeout_sec", "0.095")
add_launch_arg("input_twist_topic_type", "twist")
add_launch_arg("publish_synchronized_pointcloud", "False")

set_container_executable = SetLaunchConfiguration(
"container_executable",
Expand Down
23 changes: 23 additions & 0 deletions aip_xx1_launch/config/concatenate_and_time_sync_node.param.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
/**:
ros__parameters:
debug_mode: false
has_static_tf_only: false
rosbag_replay: false
rosbag_length: 20.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/top/pointcloud_before_sync", # 0.08
"/sensing/lidar/left/pointcloud_before_sync", # 0.00
"/sensing/lidar/right/pointcloud_before_sync", # 0.00
"/sensing/lidar/rear/pointcloud_before_sync", # 0.00
]
output_frame: base_link
lidar_timestamp_offsets: [0.0, 0.02, 0.02, 0.02]
lidar_timestamp_noise_window: [0.01, 0.01, 0.01, 0.01]
Loading

0 comments on commit b0c157b

Please sign in to comment.