@@ -71,6 +71,13 @@ def create_parameter_dict(*args):
71
71
72
72
nodes = []
73
73
74
+ nodes .append (
75
+ ComposableNode (
76
+ package = "glog_component" ,
77
+ plugin = "GlogComponent" ,
78
+ name = "glog_component" ,
79
+ )
80
+ )
74
81
cropbox_parameters = create_parameter_dict ("input_frame" , "output_frame" )
75
82
cropbox_parameters ["negative" ] = True
76
83
@@ -117,7 +124,23 @@ def create_parameter_dict(*args):
117
124
extra_arguments = [{"use_intra_process_comms" : LaunchConfiguration ("use_intra_process" )}],
118
125
)
119
126
)
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
+ )
120
142
143
+ # Ring Outlier Filter is the last component in the pipeline, so control the output frame here
121
144
if LaunchConfiguration ("output_as_sensor_frame" ).perform (context ).lower () == "true" :
122
145
ring_outlier_output_frame = {"output_frame" : LaunchConfiguration ("frame_id" )}
123
146
else :
@@ -129,7 +152,7 @@ def create_parameter_dict(*args):
129
152
name = "ring_outlier_filter" ,
130
153
remappings = [
131
154
("input" , "rectified/pointcloud_ex" ),
132
- ("output" , "pointcloud " ),
155
+ ("output" , "pointcloud_before_sync " ),
133
156
],
134
157
parameters = [ring_outlier_filter_node_param , ring_outlier_output_frame ],
135
158
extra_arguments = [{"use_intra_process_comms" : LaunchConfiguration ("use_intra_process" )}],
@@ -144,48 +167,36 @@ def create_parameter_dict(*args):
144
167
package = "rclcpp_components" ,
145
168
executable = LaunchConfiguration ("container_executable" ),
146
169
composable_node_descriptions = nodes ,
170
+ output = "both" ,
147
171
)
148
172
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
+ # )
174
184
175
185
# one way to add a ComposableNode conditional on a launch argument to a
176
186
# 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]
187
198
188
- return [container , distortion_loader , distortion_relay_loader ]
199
+ return [container ]
189
200
190
201
191
202
def generate_launch_description ():
0 commit comments