Skip to content

Commit

Permalink
feat(pointcloud_preprocessor): load_distortion_parameter_from_yaml (#93)
Browse files Browse the repository at this point in the history
* feat: load distortion parameter from yaml

Signed-off-by: vividf <yihsiang.fang@tier4.jp>

* chore: fix spell error

Signed-off-by: vividf <yihsiang.fang@tier4.jp>

* feat: modify the nebula_node_container based on tier4 internal common_sensor_launch

Signed-off-by: vividf <yihsiang.fang@tier4.jp>

* chore: use ParameterFile to load param

Signed-off-by: vividf <yihsiang.fang@tier4.jp>

---------

Signed-off-by: vividf <yihsiang.fang@tier4.jp>
  • Loading branch information
vividf authored Jul 3, 2024
1 parent a74a6cc commit bbf6398
Show file tree
Hide file tree
Showing 3 changed files with 28 additions and 3 deletions.
1 change: 1 addition & 0 deletions common_sensor_launch/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,4 +11,5 @@ endif()

ament_auto_package(INSTALL_TO_SHARE
launch
config
)
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
/**:
ros__parameters:
base_frame: base_link
use_imu: true
use_3d_distortion_correction: false
25 changes: 22 additions & 3 deletions common_sensor_launch/launch/nebula_node_container.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
from launch_ros.actions import ComposableNodeContainer
from launch_ros.actions import LoadComposableNodes
from launch_ros.descriptions import ComposableNode
from launch_ros.parameter_descriptions import ParameterFile
import yaml


Expand Down Expand Up @@ -84,6 +85,12 @@ def create_parameter_dict(*args):
sensor_calib_fp
), "Sensor calib file under calibration/ was not found: {}".format(sensor_calib_fp)

# Pointcloud preprocessor parameters
distortion_corrector_node_param = ParameterFile(
param_file=LaunchConfiguration("distortion_correction_node_param_path").perform(context),
allow_substs=True,
)

nodes = []

nodes.append(
Expand Down Expand Up @@ -184,6 +191,7 @@ def create_parameter_dict(*args):
("~/input/pointcloud", "mirror_cropped/pointcloud_ex"),
("~/output/pointcloud", "rectified/pointcloud_ex"),
],
parameters=[distortion_corrector_node_param],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)
)
Expand Down Expand Up @@ -265,6 +273,8 @@ def add_launch_arg(name: str, default_value=None, description=None):
DeclareLaunchArgument(name, default_value=default_value, description=description)
)

common_sensor_share_dir = get_package_share_directory("common_sensor_launch")

add_launch_arg("sensor_model", description="sensor model name")
add_launch_arg("config_file", "", description="sensor configuration file")
add_launch_arg("launch_driver", "True", "do launch driver")
Expand All @@ -285,13 +295,22 @@ def add_launch_arg(name: str, default_value=None, description=None):
add_launch_arg("frame_id", "lidar", "frame id")
add_launch_arg("input_frame", LaunchConfiguration("base_frame"), "use for cropbox")
add_launch_arg("output_frame", LaunchConfiguration("base_frame"), "use for cropbox")
add_launch_arg(
"vehicle_mirror_param_file", description="path to the file of vehicle mirror position yaml"
)
add_launch_arg("use_multithread", "False", "use multithread")
add_launch_arg("use_intra_process", "False", "use ROS 2 component container communication")
add_launch_arg("lidar_container_name", "nebula_node_container")
add_launch_arg("output_as_sensor_frame", "True", "output final pointcloud in sensor frame")
add_launch_arg(
"vehicle_mirror_param_file", description="path to the file of vehicle mirror position yaml"
)
add_launch_arg(
"distortion_correction_node_param_path",
os.path.join(
common_sensor_share_dir,
"config",
"distortion_corrector_node.param.yaml",
),
description="path to parameter file of distortion correction node",
)

set_container_executable = SetLaunchConfiguration(
"container_executable",
Expand Down

0 comments on commit bbf6398

Please sign in to comment.