11
11
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12
12
# See the License for the specific language governing permissions and
13
13
# limitations under the License.
14
-
14
+ import os
15
+ from ament_index_python .packages import get_package_share_directory
15
16
import launch
16
17
from launch .actions import DeclareLaunchArgument
17
18
from launch .actions import OpaqueFunction
22
23
from launch_ros .actions import ComposableNodeContainer
23
24
from launch_ros .actions import LoadComposableNodes
24
25
from launch_ros .descriptions import ComposableNode
26
+ from launch_ros .parameter_descriptions import ParameterFile
25
27
import yaml
26
28
27
29
@@ -57,8 +59,25 @@ def create_parameter_dict(*args):
57
59
result [x ] = LaunchConfiguration (x )
58
60
return result
59
61
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
+
60
72
nodes = []
61
73
74
+ nodes .append (
75
+ ComposableNode (
76
+ package = "glog_component" ,
77
+ plugin = "GlogComponent" ,
78
+ name = "glog_component" ,
79
+ )
80
+ )
62
81
cropbox_parameters = create_parameter_dict ("input_frame" , "output_frame" )
63
82
cropbox_parameters ["negative" ] = True
64
83
@@ -105,16 +124,37 @@ def create_parameter_dict(*args):
105
124
extra_arguments = [{"use_intra_process_comms" : LaunchConfiguration ("use_intra_process" )}],
106
125
)
107
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
+ )
108
142
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
109
148
nodes .append (
110
149
ComposableNode (
111
150
package = "autoware_pointcloud_preprocessor" ,
112
151
plugin = "autoware::pointcloud_preprocessor::RingOutlierFilterComponent" ,
113
152
name = "ring_outlier_filter" ,
114
153
remappings = [
115
154
("input" , "rectified/pointcloud_ex" ),
116
- ("output" , "pointcloud " ),
155
+ ("output" , "pointcloud_before_sync " ),
117
156
],
157
+ parameters = [ring_outlier_filter_node_param ],
118
158
extra_arguments = [{"use_intra_process_comms" : LaunchConfiguration ("use_intra_process" )}],
119
159
)
120
160
)
@@ -127,47 +167,10 @@ def create_parameter_dict(*args):
127
167
package = "rclcpp_components" ,
128
168
executable = LaunchConfiguration ("container_executable" ),
129
169
composable_node_descriptions = nodes ,
170
+ output = "both" ,
130
171
)
131
172
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 ]
171
174
172
175
173
176
def generate_launch_description ():
@@ -178,17 +181,38 @@ def add_launch_arg(name: str, default_value=None, description=None):
178
181
launch_arguments .append (
179
182
DeclareLaunchArgument (name , default_value = default_value , description = description )
180
183
)
184
+
185
+ common_sensor_share_dir = get_package_share_directory ("common_sensor_launch" )
181
186
182
187
add_launch_arg ("base_frame" , "base_link" , "base frame id" )
183
188
add_launch_arg ("container_name" , "velodyne_composable_node_container" , "container name" )
184
189
add_launch_arg ("input_frame" , LaunchConfiguration ("base_frame" ), "use for cropbox" )
185
190
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" )
186
192
add_launch_arg (
187
193
"vehicle_mirror_param_file" , description = "path to the file of vehicle mirror position yaml"
188
194
)
195
+ add_launch_arg ("frame_id" , "lidar" , "frame id" )
189
196
add_launch_arg ("use_multithread" , "False" , "use multithread" )
190
197
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
+ )
192
216
set_container_executable = SetLaunchConfiguration (
193
217
"container_executable" ,
194
218
"component_container" ,
0 commit comments