Skip to content

Commit

Permalink
feat(sample_sensor_kit_launch): concatenate node load from parameter …
Browse files Browse the repository at this point in the history
…file (#108)

* feat: concatenate node load from parameter file

Signed-off-by: vividf <[email protected]>

* chore: update params

Signed-off-by: vividf <[email protected]>

* chore: add use_naive_approach

Signed-off-by: vividf <[email protected]>

* chore: remove space

Signed-off-by: vividf <[email protected]>

* feat: add matching strategy params

Signed-off-by: vividf <[email protected]>

---------

Signed-off-by: vividf <[email protected]>
  • Loading branch information
vividf authored Jan 21, 2025
1 parent b12f176 commit e6f3356
Show file tree
Hide file tree
Showing 2 changed files with 45 additions and 12 deletions.
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_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/right/pointcloud_before_sync",
"/sensing/lidar/top/pointcloud_before_sync",
"/sensing/lidar/left/pointcloud_before_sync",
]
output_frame: base_link
matching_strategy:
type: advanced
lidar_timestamp_offsets: [0.0, 0.015, 0.016]
lidar_timestamp_noise_window: [0.01, 0.01, 0.01]
34 changes: 22 additions & 12 deletions sample_sensor_kit_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,18 +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/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,
}
],
parameters=[concatenate_and_time_sync_node_param],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)

Expand All @@ -65,10 +65,20 @@ def generate_launch_description():
def add_launch_arg(name: str, default_value=None):
launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value))

sample_sensor_kit_launch_share_dir = get_package_share_directory("sample_sensor_kit_launch")

add_launch_arg("base_frame", "base_link")
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(
sample_sensor_kit_launch_share_dir,
"config",
"concatenate_and_time_sync_node.param.yaml",
),
)

set_container_executable = SetLaunchConfiguration(
"container_executable",
Expand Down

0 comments on commit e6f3356

Please sign in to comment.