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

Commit 5bce945

Browse files
committed
fix topic names
Signed-off-by: A. Sena Yılmaz <[email protected]>
1 parent 5aff1f1 commit 5bce945

File tree

2 files changed

+52
-40
lines changed

2 files changed

+52
-40
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")}],

common_awsim_labs_sensor_launch/launch/velodyne_node_container.launch.py

+48-37
Original file line numberDiff line numberDiff line change
@@ -71,6 +71,13 @@ def create_parameter_dict(*args):
7171

7272
nodes = []
7373

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

@@ -117,7 +124,23 @@ def create_parameter_dict(*args):
117124
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
118125
)
119126
)
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+
)
120142

143+
# Ring Outlier Filter is the last component in the pipeline, so control the output frame here
121144
if LaunchConfiguration("output_as_sensor_frame").perform(context).lower() == "true":
122145
ring_outlier_output_frame = {"output_frame": LaunchConfiguration("frame_id")}
123146
else:
@@ -129,7 +152,7 @@ def create_parameter_dict(*args):
129152
name="ring_outlier_filter",
130153
remappings=[
131154
("input", "rectified/pointcloud_ex"),
132-
("output", "pointcloud"),
155+
("output", "pointcloud_before_sync"),
133156
],
134157
parameters=[ring_outlier_filter_node_param, ring_outlier_output_frame],
135158
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
@@ -144,48 +167,36 @@ def create_parameter_dict(*args):
144167
package="rclcpp_components",
145168
executable=LaunchConfiguration("container_executable"),
146169
composable_node_descriptions=nodes,
170+
output="both",
147171
)
148172

149-
distortion_component = ComposableNode(
150-
package="autoware_pointcloud_preprocessor",
151-
plugin="autoware::pointcloud_preprocessor::DistortionCorrectorComponent",
152-
name="distortion_corrector_node",
153-
remappings=[
154-
("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"),
155-
("~/input/imu", "/sensing/imu/imu_data"),
156-
("~/input/pointcloud", "mirror_cropped/pointcloud_ex"),
157-
("~/output/pointcloud", "rectified/pointcloud_ex"),
158-
],
159-
parameters=[distortion_corrector_node_param],
160-
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
161-
)
162-
163-
distortion_relay_component = ComposableNode(
164-
package="topic_tools",
165-
plugin="topic_tools::RelayNode",
166-
name="pointcloud_distortion_relay",
167-
namespace="",
168-
parameters=[
169-
{"input_topic": "mirror_cropped/pointcloud_ex"},
170-
{"output_topic": "rectified/pointcloud_ex"}
171-
],
172-
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
173-
)
173+
# distortion_relay_component = ComposableNode(
174+
# package="topic_tools",
175+
# plugin="topic_tools::RelayNode",
176+
# name="pointcloud_distortion_relay",
177+
# namespace="",
178+
# parameters=[
179+
# {"input_topic": "mirror_cropped/pointcloud_ex"},
180+
# {"output_topic": "rectified/pointcloud_ex"}
181+
# ],
182+
# extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
183+
# )
174184

175185
# one way to add a ComposableNode conditional on a launch argument to a
176186
# container. The `ComposableNode` itself doesn't accept a condition
177-
distortion_loader = LoadComposableNodes(
178-
composable_node_descriptions=[distortion_component],
179-
target_container=container,
180-
condition=launch.conditions.IfCondition(LaunchConfiguration("use_distortion_corrector")),
181-
)
182-
distortion_relay_loader = LoadComposableNodes(
183-
composable_node_descriptions=[distortion_relay_component],
184-
target_container=container,
185-
condition=launch.conditions.UnlessCondition(LaunchConfiguration("use_distortion_corrector")),
186-
)
187+
# distortion_loader = LoadComposableNodes(
188+
# composable_node_descriptions=[distortion_component],
189+
# target_container=container,
190+
# condition=launch.conditions.IfCondition(LaunchConfiguration("use_distortion_corrector")),
191+
# )
192+
# distortion_relay_loader = LoadComposableNodes(
193+
# composable_node_descriptions=[distortion_relay_component],
194+
# target_container=container,
195+
# condition=launch.conditions.UnlessCondition(LaunchConfiguration("use_distortion_corrector")),
196+
# )
197+
# return [container, distortion_loader, distortion_relay_loader]
187198

188-
return [container, distortion_loader, distortion_relay_loader]
199+
return [container]
189200

190201

191202
def generate_launch_description():

0 commit comments

Comments
 (0)