Skip to content
This repository was archived by the owner on Apr 1, 2025. It is now read-only.

Commit 3695cab

Browse files
authored
feat: ring outlier filter and distortion correction node load from param file (#6)
Signed-off-by: A. Sena Yılmaz <[email protected]>
1 parent dbce284 commit 3695cab

File tree

4 files changed

+89
-45
lines changed

4 files changed

+89
-45
lines changed

awsim_labs_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py

+4-3
Original file line numberDiff line numberDiff line change
@@ -39,13 +39,14 @@ def launch_setup(context, *args, **kwargs):
3939
parameters=[
4040
{
4141
"input_topics": [
42-
"/sensing/lidar/top/pointcloud",
43-
"/sensing/lidar/left/pointcloud",
44-
"/sensing/lidar/right/pointcloud",
42+
"/sensing/lidar/top/pointcloud_before_sync",
43+
"/sensing/lidar/left/pointcloud_before_sync",
44+
"/sensing/lidar/right/pointcloud_before_sync",
4545
],
4646
"output_frame": LaunchConfiguration("base_frame"),
4747
"timeout_sec": 0.01,
4848
"input_twist_topic_type": "twist",
49+
"publish_synchronized_pointcloud": True,
4950
}
5051
],
5152
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
/**:
2+
ros__parameters:
3+
base_frame: base_link
4+
use_imu: true
5+
use_3d_distortion_correction: false
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,14 @@
1+
/**:
2+
ros__parameters:
3+
distance_ratio: 1.03
4+
object_length_threshold: 0.1
5+
num_points_threshold: 4
6+
max_rings_num: 128
7+
max_points_num_per_ring: 4000
8+
publish_outlier_pointcloud: false
9+
min_azimuth_deg: 0.0
10+
max_azimuth_deg: 360.0
11+
max_distance: 12.0
12+
vertical_bins: 128
13+
horizontal_bins: 36
14+
noise_threshold: 2

common_awsim_labs_sensor_launch/launch/velodyne_node_container.launch.py

+66-42
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,8 @@
1111
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
14-
14+
import os
15+
from ament_index_python.packages import get_package_share_directory
1516
import launch
1617
from launch.actions import DeclareLaunchArgument
1718
from launch.actions import OpaqueFunction
@@ -22,6 +23,7 @@
2223
from launch_ros.actions import ComposableNodeContainer
2324
from launch_ros.actions import LoadComposableNodes
2425
from launch_ros.descriptions import ComposableNode
26+
from launch_ros.parameter_descriptions import ParameterFile
2527
import yaml
2628

2729

@@ -57,8 +59,25 @@ def create_parameter_dict(*args):
5759
result[x] = LaunchConfiguration(x)
5860
return result
5961

62+
# Pointcloud preprocessor parameters
63+
distortion_corrector_node_param = ParameterFile(
64+
param_file=LaunchConfiguration("distortion_correction_node_param_path").perform(context),
65+
allow_substs=True,
66+
)
67+
ring_outlier_filter_node_param = ParameterFile(
68+
param_file=LaunchConfiguration("ring_outlier_filter_node_param_path").perform(context),
69+
allow_substs=True,
70+
)
71+
6072
nodes = []
6173

74+
nodes.append(
75+
ComposableNode(
76+
package="glog_component",
77+
plugin="GlogComponent",
78+
name="glog_component",
79+
)
80+
)
6281
cropbox_parameters = create_parameter_dict("input_frame", "output_frame")
6382
cropbox_parameters["negative"] = True
6483

@@ -105,16 +124,37 @@ def create_parameter_dict(*args):
105124
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
106125
)
107126
)
127+
nodes.append(
128+
ComposableNode(
129+
package="autoware_pointcloud_preprocessor",
130+
plugin="autoware::pointcloud_preprocessor::DistortionCorrectorComponent",
131+
name="distortion_corrector_node",
132+
remappings=[
133+
("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"),
134+
("~/input/imu", "/sensing/imu/imu_data"),
135+
("~/input/pointcloud", "mirror_cropped/pointcloud_ex"),
136+
("~/output/pointcloud", "rectified/pointcloud_ex"),
137+
],
138+
parameters=[distortion_corrector_node_param],
139+
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
140+
)
141+
)
108142

143+
# Ring Outlier Filter is the last component in the pipeline, so control the output frame here
144+
# if LaunchConfiguration("output_as_sensor_frame").perform(context).lower() == "true":
145+
# ring_outlier_output_frame = {"output_frame": LaunchConfiguration("frame_id")}
146+
# else:
147+
# ring_outlier_output_frame = {"output_frame": ""} # keep the output frame as the input frame
109148
nodes.append(
110149
ComposableNode(
111150
package="autoware_pointcloud_preprocessor",
112151
plugin="autoware::pointcloud_preprocessor::RingOutlierFilterComponent",
113152
name="ring_outlier_filter",
114153
remappings=[
115154
("input", "rectified/pointcloud_ex"),
116-
("output", "pointcloud"),
155+
("output", "pointcloud_before_sync"),
117156
],
157+
parameters=[ring_outlier_filter_node_param],
118158
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
119159
)
120160
)
@@ -127,47 +167,10 @@ def create_parameter_dict(*args):
127167
package="rclcpp_components",
128168
executable=LaunchConfiguration("container_executable"),
129169
composable_node_descriptions=nodes,
170+
output="both",
130171
)
131172

132-
distortion_component = ComposableNode(
133-
package="autoware_pointcloud_preprocessor",
134-
plugin="autoware::pointcloud_preprocessor::DistortionCorrectorComponent",
135-
name="distortion_corrector_node",
136-
remappings=[
137-
("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"),
138-
("~/input/imu", "/sensing/imu/imu_data"),
139-
("~/input/pointcloud", "mirror_cropped/pointcloud_ex"),
140-
("~/output/pointcloud", "rectified/pointcloud_ex"),
141-
],
142-
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
143-
)
144-
145-
distortion_relay_component = ComposableNode(
146-
package="topic_tools",
147-
plugin="topic_tools::RelayNode",
148-
name="pointcloud_distortion_relay",
149-
namespace="",
150-
parameters=[
151-
{"input_topic": "mirror_cropped/pointcloud_ex"},
152-
{"output_topic": "rectified/pointcloud_ex"}
153-
],
154-
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
155-
)
156-
157-
# one way to add a ComposableNode conditional on a launch argument to a
158-
# container. The `ComposableNode` itself doesn't accept a condition
159-
distortion_loader = LoadComposableNodes(
160-
composable_node_descriptions=[distortion_component],
161-
target_container=container,
162-
condition=launch.conditions.IfCondition(LaunchConfiguration("use_distortion_corrector")),
163-
)
164-
distortion_relay_loader = LoadComposableNodes(
165-
composable_node_descriptions=[distortion_relay_component],
166-
target_container=container,
167-
condition=launch.conditions.UnlessCondition(LaunchConfiguration("use_distortion_corrector")),
168-
)
169-
170-
return [container, distortion_loader, distortion_relay_loader]
173+
return [container]
171174

172175

173176
def generate_launch_description():
@@ -178,17 +181,38 @@ def add_launch_arg(name: str, default_value=None, description=None):
178181
launch_arguments.append(
179182
DeclareLaunchArgument(name, default_value=default_value, description=description)
180183
)
184+
185+
common_sensor_share_dir = get_package_share_directory("common_sensor_launch")
181186

182187
add_launch_arg("base_frame", "base_link", "base frame id")
183188
add_launch_arg("container_name", "velodyne_composable_node_container", "container name")
184189
add_launch_arg("input_frame", LaunchConfiguration("base_frame"), "use for cropbox")
185190
add_launch_arg("output_frame", LaunchConfiguration("base_frame"), "use for cropbox")
191+
add_launch_arg("output_as_sensor_frame", "True", "output final pointcloud in sensor frame")
186192
add_launch_arg(
187193
"vehicle_mirror_param_file", description="path to the file of vehicle mirror position yaml"
188194
)
195+
add_launch_arg("frame_id", "lidar", "frame id")
189196
add_launch_arg("use_multithread", "False", "use multithread")
190197
add_launch_arg("use_intra_process", "False", "use ROS2 component container communication")
191-
198+
add_launch_arg(
199+
"distortion_correction_node_param_path",
200+
os.path.join(
201+
common_sensor_share_dir,
202+
"config",
203+
"distortion_corrector_node.param.yaml",
204+
),
205+
description="path to parameter file of distortion correction node",
206+
)
207+
add_launch_arg(
208+
"ring_outlier_filter_node_param_path",
209+
os.path.join(
210+
common_sensor_share_dir,
211+
"config",
212+
"ring_outlier_filter_node.param.yaml",
213+
),
214+
description="path to parameter file of ring outlier filter node",
215+
)
192216
set_container_executable = SetLaunchConfiguration(
193217
"container_executable",
194218
"component_container",

0 commit comments

Comments
 (0)