Skip to content

Commit 6e14982

Browse files
authored
fix: integration miss related to camera lidar fusion (autowarefoundation#481)
* fix integration miss Signed-off-by: Yukihiro Saito <yukky.saito@gmail.com> * bug fix Signed-off-by: Yukihiro Saito <yukky.saito@gmail.com> * add detection by tracker Signed-off-by: Yukihiro Saito <yukky.saito@gmail.com> * Update launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml
1 parent 5c9302d commit 6e14982

File tree

6 files changed

+43
-19
lines changed

6 files changed

+43
-19
lines changed

launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml

+28-6
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,7 @@
3737
<push-ros-namespace namespace="euclidean"/>
3838
<include file="$(find-pkg-share euclidean_cluster)/launch/voxel_grid_based_euclidean_cluster.launch.xml">
3939
<arg name="output_clusters" value="lidar/clusters"/>
40+
<arg name="use_pointcloud_map" value="false"/>
4041
</include>
4142
<include file="$(find-pkg-share roi_cluster_fusion)/launch/roi_cluster_fusion.launch.xml">
4243
<arg name="input/camera_info0" value="$(var camera_info0)"/>
@@ -68,10 +69,8 @@
6869
<arg name="output" value="camera_lidar_fusion/clusters"/>
6970
</include>
7071
<include file="$(find-pkg-share shape_estimation)/launch/shape_estimation.launch.xml">
71-
<arg name="use_map_current" value="$(var use_vector_map)"/>
7272
<arg name="input/objects" value="camera_lidar_fusion/clusters" />
7373
<arg name="output/objects" value="camera_lidar_fusion/objects_with_feature" />
74-
<arg name="orientation_reliable" value="false"/>
7574
</include>
7675
<!-- convert DynamicObjectsWithFeatureArray to DynamicObjects -->
7776
<include file="$(find-pkg-share detected_object_feature_remover)/launch/detected_object_feature_remover.launch.xml">
@@ -86,25 +85,48 @@
8685
</include>
8786
</group>
8887

88+
<!-- CenterPoint -->
8989
<group if="$(eval &quot;'$(var lidar_detection_model)'=='centerpoint'&quot;)">
9090
<push-ros-namespace namespace="centerpoint"/>
9191
<include file="$(find-pkg-share lidar_centerpoint)/launch/lidar_centerpoint.launch.xml">
9292
<arg name="output/objects" value="objects" />
9393
</include>
9494
</group>
9595

96+
<!-- Lidar Apollo Instance Segmentation -->
9697
<group if="$(eval &quot;'$(var lidar_detection_model)'=='apollo'&quot;)">
9798
<push-ros-namespace namespace="apollo"/>
98-
<include file="$(find-pkg-share lidar_apollo_instance_segmentation)/launch/lidar_apollo_instance_segmentation.launch.xml" />
99-
<include file="$(find-pkg-share shape_estimation)/launch/shape_estimation.launch.xml">
100-
<arg name="output/objects" value="objects"/>
101-
<arg name="use_map_current" value="$(var use_vector_map)"/>
99+
<group>
100+
<include file="$(find-pkg-share lidar_apollo_instance_segmentation)/launch/lidar_apollo_instance_segmentation.launch.xml" />
101+
<include file="$(find-pkg-share shape_estimation)/launch/shape_estimation.launch.xml">
102+
<arg name="output/objects" value="objects_with_feature"/>
103+
<arg name="use_vehicle_reference_yaw" value="true"/>
104+
</include>
105+
<!-- convert DynamicObjectsWithFeatureArray to DynamicObjects -->
106+
<include file="$(find-pkg-share detected_object_feature_remover)/launch/detected_object_feature_remover.launch.xml">
107+
<arg name="input" value="objects_with_feature" />
108+
<arg name="output" value="objects" />
109+
</include>
110+
</group>
111+
</group>
112+
113+
<!-- DetectionByTracker -->
114+
<group>
115+
<push-ros-namespace namespace="detection_by_tracker"/>
116+
<include file="$(find-pkg-share detection_by_tracker)/launch/detection_by_tracker.launch.xml">
102117
</include>
103118
</group>
104119

120+
<!-- Merger -->
105121
<include file="$(find-pkg-share object_merger)/launch/object_association_merger.launch.xml">
106122
<arg name="input/object0" value="$(var lidar_detection_model)/objects"/>
107123
<arg name="input/object1" value="euclidean/camera_lidar_fusion/short_range_objects"/>
124+
<arg name="output/object" value="camera_lidar_fusion/objects"/>
125+
</include>
126+
<include file="$(find-pkg-share object_merger)/launch/object_association_merger.launch.xml">
127+
<arg name="input/object0" value="detection_by_tracker/objects"/>
128+
<arg name="input/object1" value="camera_lidar_fusion/objects"/>
108129
<arg name="output/object" value="objects"/>
109130
</include>
131+
110132
</launch>

launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@
3333
<include file="$(find-pkg-share lidar_apollo_instance_segmentation)/launch/lidar_apollo_instance_segmentation.launch.xml" />
3434
<include file="$(find-pkg-share shape_estimation)/launch/shape_estimation.launch.xml">
3535
<arg name="output/objects" value="objects_with_feature"/>
36-
<arg name="use_map_current" value="$(var use_vector_map)"/>
36+
<arg name="use_vehicle_reference_yaw" value="true"/>
3737
</include>
3838
<!-- convert DynamicObjectsWithFeatureArray to DynamicObjects -->
3939
<include file="$(find-pkg-share detected_object_feature_remover)/launch/detected_object_feature_remover.launch.xml">

perception/roi_cluster_fusion/src/roi_cluster_fusion_nodelet.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@ Debugger::Debugger(rclcpp::Node * node, const int camera_num) : node_(node)
4747
for (int id = 0; id < camera_num; ++id) {
4848
auto sub = image_transport::create_subscription(
4949
node, "input/image_raw" + std::to_string(id),
50-
boost::bind(&Debugger::imageCallback, this, _1, id), "raw");
50+
boost::bind(&Debugger::imageCallback, this, _1, id), "raw", rmw_qos_profile_sensor_data);
5151
image_subs_.push_back(sub);
5252
if (node->has_parameter("format")) {
5353
node->undeclare_parameter("format");

perception/shape_estimation/launch/shape_estimation.launch.xml

+3-3
Original file line numberDiff line numberDiff line change
@@ -2,15 +2,15 @@
22

33
<arg name="input/objects" default="labeled_clusters"/>
44
<arg name="output/objects" default="shape_estimated_objects"/>
5-
<arg name="use_map_current" default="true"/>
5+
<arg name="use_filter" default="true"/>
66
<arg name="use_corrector" default="true"/>
77
<arg name="node_name" default="shape_estimation"/>
8-
<arg name="use_vehicle_reference_yaw" default="true"/>
8+
<arg name="use_vehicle_reference_yaw" default="false"/>
99
<node pkg="shape_estimation" exec="shape_estimation" name="$(var node_name)" output="screen">
1010
<remap from="input" to="$(var input/objects)" />
1111
<remap from="objects" to="$(var output/objects)" />
12+
<param name="use_filter" value="$(var use_filter)" />
1213
<param name="use_corrector" value="$(var use_corrector)" />
13-
<param name="use_map_current" value="$(var use_map_current)" />
1414
<param name="use_vehicle_reference_yaw" value="$(var use_vehicle_reference_yaw)"/>
1515
</node>
1616
</launch>

sensing/image_transport_decompressor/CMakeLists.txt

+3-1
Original file line numberDiff line numberDiff line change
@@ -39,4 +39,6 @@ if(BUILD_TESTING)
3939
ament_lint_auto_find_test_dependencies()
4040
endif()
4141

42-
ament_auto_package()
42+
ament_auto_package(INSTALL_TO_SHARE
43+
launch
44+
)
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,9 @@
11
<launch>
2-
<arg name="input_topic_name" default="/input/compressed_image" />
3-
<arg name="output_topic_name" default="/output/raw_image" />
2+
<arg name="input_topic_name" default="/input/compressed_image" />
3+
<arg name="output_topic_name" default="/output/raw_image" />
44

5-
<node pkg="image_transport_decompressor" exec="image_transport_decompressor_node" name="image_transport_decompressor_node">
6-
<remap from="input" to="$(var input_topic_name)" />
7-
<remap from="output" to="$(var output_topic_name)" />
8-
</node>
9-
</launch>
5+
<node pkg="image_transport_decompressor" exec="image_transport_decompressor_node" name="$(anon image_transport_decompressor_node)">
6+
<remap from="~/input/compressed_image" to="$(var input_topic_name)" />
7+
<remap from="~/output/raw_image" to="$(var output_topic_name)" />
8+
</node>
9+
</launch>

0 commit comments

Comments
 (0)