Skip to content

Commit a575a9e

Browse files
YoheiMishinamitsudome-raohsatonnmmnik-tier4
authoredDec 6, 2021
feat: add roi cluster fusion package (autowarefoundation#116)
* release v0.4.0 * Modify to use projection matrix with undistorted 2D result (autowarefoundation#722) Signed-off-by: Akihito Ohasto <aohsato@gmail.com> * remove ROS1 packages temporarily Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp> * Revert "remove ROS1 packages temporarily" This reverts commit 6e1593f7d630fc1e670df40fe1723890fc238f17. Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp> * add COLCON_IGNORE to ros1 packages Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp> * Rename launch files to launch.xml (autowarefoundation#28) * Rename h files to hpp (autowarefoundation#142) * Change includes * Rename files * Adjustments to make things compile * Other packages * Adjust copyright notice on 532 out of 699 source files (autowarefoundation#143) * Use quotes for includes where appropriate (autowarefoundation#144) * Use quotes for includes where appropriate * Fix lint tests * Make tests pass hopefully * ported roi_cluster_fusion from ROS1 to ROS2 (autowarefoundation#118) compiles succesfully. Getting some undefined reference error while launching the node. * Port euclidean cluster (autowarefoundation#120) * porting CmakeLists.txt and package.xml in progress * ported CMakeLists.txt and package.xml to ROS2 * Ported euclidean_cluster from ROS1 to ROS2 * deleted unnecesary files * fixed transient_local Co-authored-by: Takamasa Horibe <horibe.takamasa@gmail.com> * hotfix roi_cluster_fusion (autowarefoundation#239) * Fix perception launches (autowarefoundation#240) * fix roi_cluster_fusion launch Signed-off-by: Takamasa Horibe <takamasa.horib@gmail.com> * add comment on launch Signed-off-by: Takamasa Horibe <takamasa.horib@gmail.com> Co-authored-by: Takamasa Horibe <takamasa.horib@gmail.com> * Ros2 v0.8.0 roi cluster fusion (autowarefoundation#321) * restore v0.5.0 * Feature/fusion debug (autowarefoundation#1051) * add debuger * change param * add publisher * Compatible with opencv4 (autowarefoundation#1156) Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp> * refactor for ros2 style * fix code * to hpp * fix code * uncursify Co-authored-by: Yukihiro Saito <yukky.saito@gmail.com> Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> * [roi_cluster_fusion]: Avoid redeclaring parameter for compressed image publisher (autowarefoundation#346) Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp> * Fix transform (autowarefoundation#420) * Replace rclcpp::Time(0) by tf2::TimePointZero() in lookupTransform Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Fix canTransform Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Fix test Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Fix typo in perception module (autowarefoundation#440) * add use_sim-time option (autowarefoundation#454) * Format launch files (autowarefoundation#1219) Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Unify Apache-2.0 license name (autowarefoundation#1242) * Remove use_sim_time for set_parameter (autowarefoundation#1260) Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp> * Add pre-commit (autowarefoundation#1560) * add pre-commit * add pre-commit-config * add additional settings for private repository * use default pre-commit-config * update pre-commit setting * Ignore whitespace for line breaks in markdown * Update .github/workflows/pre-commit.yml Co-authored-by: Kazuki Miyahara <kmiya@outlook.com> * exclude svg * remove pretty-format-json * add double-quote-string-fixer * consider COLCON_IGNORE file when seaching modified package * format file * pre-commit fixes * Update pre-commit.yml * Update .pre-commit-config.yaml Co-authored-by: Kazuki Miyahara <kmiya@outlook.com> Co-authored-by: pre-commit <pre-commit@example.com> Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> * Fix -Wunused-parameter (autowarefoundation#1836) * Fix -Wunused-parameter Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Fix mistake Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * fix spell * Fix lint issues Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Ignore flake8 warnings Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> Co-authored-by: Hiroki OTA <hiroki.ota@tier4.jp> * add sort-package-xml hook in pre-commit (autowarefoundation#1881) * add sort xml hook in pre-commit * change retval to exit_status * rename * add prettier plugin-xml * use early return * add license note * add tier4 license * restore prettier * change license order * move local hooks to public repo * move prettier-xml to pre-commit-hooks-ros * update version for bug-fix * apply pre-commit * [roi_cluster_fusion]: Fix poting mistake (autowarefoundation#1624) Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp> * fix typo & check debugger (autowarefoundation#1511) (autowarefoundation#1625) Co-authored-by: Yusuke Muramatsu <yukke42@users.noreply.github.com> * Use set_remap for if tag (autowarefoundation#1800) Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp> * Apply format (autowarefoundation#1999) Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> Fix cpplint Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Detection by tracker (autowarefoundation#1910) * initial commit * backup * apply format * cosmetic change * implement divided under segmenterd clusters * cosmetic change * bug fix * bug fix * bug fix * modify launch * add debug and bug fix * bug fix * bug fix * add no found tracked object * modify parameters and cmake * bug fix * remove debug info * add readme * modify clustering launch * run pre-commit * cosmetic change * cosmetic change * cosmetic change * apply markdownlint * modify launch * modify for cpplint * modify qos * change int to size_T * bug fix * change perception qos * Update perception/object_recognition/detection/detection_by_tracker/package.xml Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> * cosmetic change * cosmetic change * fix launch * Update perception/object_recognition/detection/detection_by_tracker/src/utils.cpp Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> * modify header include order * change include order * Update perception/object_recognition/detection/detection_by_tracker/src/detection_by_tracker_core.cpp Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> * change to std::optional * cosmetic change * Update perception/object_recognition/detection/detection_by_tracker/src/detection_by_tracker_core.cpp Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> * Update perception/object_recognition/detection/detection_by_tracker/src/detection_by_tracker_core.cpp Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> * bug fix * modify readme Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> * sync rc rc/v0.23.0 (autowarefoundation#2219) * Fix qos in roi cluster fusion (autowarefoundation#2218) * fix confidence (autowarefoundation#2220) Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Co-authored-by: Yukihiro Saito <yukky.saito@gmail.com> * Change formatter to clang-format and black (autowarefoundation#2332) * Revert "Temporarily comment out pre-commit hooks" This reverts commit 748e9cdb145ce12f8b520bcbd97f5ff899fc28a3. * Replace ament_lint_common with autoware_lint_common Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Remove ament_cmake_uncrustify and ament_clang_format Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Apply Black Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Apply clang-format Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Fix build errors Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Fix for cpplint * Fix include double quotes to angle brackets Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Apply clang-format Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Fix build errors Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * Add COLCON_IGNORE (autowarefoundation#500) Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * port roi cluster fusion (autowarefoundation#536) * remove COLCON_IGNORE * use DetectedObjectsWithFeature * fix topic type * update overwrite condition * add README of roi_cluster_fusion (autowarefoundation#653) * add README of roi_cluster_fusion * fix typo Co-authored-by: Kazuki Miyahara <kmiya@outlook.com> * add image Co-authored-by: Kazuki Miyahara <kmiya@outlook.com> Co-authored-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp> Co-authored-by: Akihito Ohsato <aohsato@gmail.com> Co-authored-by: Nikolai Morin <nnmmgit@gmail.com> Co-authored-by: nik-tier4 <71747268+nik-tier4@users.noreply.github.com> Co-authored-by: Takamasa Horibe <horibe.takamasa@gmail.com> Co-authored-by: Takamasa Horibe <takamasa.horib@gmail.com> Co-authored-by: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com> Co-authored-by: Yukihiro Saito <yukky.saito@gmail.com> Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: Kazuki Miyahara <kmiya@outlook.com> Co-authored-by: tkimura4 <tomoya.kimura@tier4.jp> Co-authored-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com> Co-authored-by: pre-commit <pre-commit@example.com> Co-authored-by: Hiroki OTA <hiroki.ota@tier4.jp> Co-authored-by: Yusuke Muramatsu <yukke42@users.noreply.github.com> Co-authored-by: Kenji Miyake <kenji.miyake@tier4.jp> Co-authored-by: autoware-iv-sync-ci[bot] <87871706+autoware-iv-sync-ci[bot]@users.noreply.github.com> Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Co-authored-by: Takeshi Miura <57553950+1222-takeshi@users.noreply.github.com>
1 parent 7dd097d commit a575a9e

File tree

7 files changed

+887
-0
lines changed

7 files changed

+887
-0
lines changed
 
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,44 @@
1+
cmake_minimum_required(VERSION 3.5)
2+
project(roi_cluster_fusion)
3+
4+
if(NOT CMAKE_CXX_STANDARD)
5+
set(CMAKE_CXX_STANDARD 14)
6+
endif()
7+
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
8+
add_compile_options(-Wall -Wextra -Wpedantic)
9+
endif()
10+
11+
12+
find_package(ament_lint_auto REQUIRED)
13+
find_package(ament_cmake_auto REQUIRED)
14+
find_package(OpenCV REQUIRED)
15+
find_package(Eigen3 REQUIRED)
16+
17+
ament_auto_find_build_dependencies()
18+
19+
20+
include_directories(
21+
include
22+
${OpenCV_INCLUDE_DIRS}
23+
${EIGEN3_INCLUDE_DIR}
24+
)
25+
26+
ament_auto_add_library(roi_cluster_fusion_nodelet SHARED src/roi_cluster_fusion_nodelet.cpp)
27+
target_link_libraries(roi_cluster_fusion_nodelet
28+
${OpenCV_LIBRARIES}
29+
${EIGEN3_LIBRARIES}
30+
)
31+
32+
rclcpp_components_register_node(roi_cluster_fusion_nodelet
33+
PLUGIN "roi_cluster_fusion::RoiClusterFusionNodelet"
34+
EXECUTABLE roi_cluster_fusion_node
35+
)
36+
37+
ament_auto_package(INSTALL_TO_SHARE
38+
launch
39+
)
40+
41+
if(BUILD_TESTING)
42+
find_package(ament_lint_auto REQUIRED)
43+
ament_lint_auto_find_test_dependencies()
44+
endif()
+90
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,90 @@
1+
# roi_cluster_fusion
2+
3+
## Purpose
4+
5+
roi_cluster_fusion is a package for filtering clusters that are less likely to be objects and overwriting labels of clusters with that of Region Of Interests (ROIs) by a 2D object detector.
6+
7+
## Inner-workings / Algorithms
8+
9+
The clusters are projected onto image planes, and then if the ROIs of clusters and ROIs by a detector are overlapped, the labels of clusters are overwritten with that of ROIs by detector. Intersection over Union (IoU) is used to determine if there are overlaps between them.
10+
11+
![roi_cluster_fusion_image](./images/roi_cluster_fusion.png)
12+
13+
## Inputs / Outputs
14+
15+
### Input
16+
17+
| Name | Type | Description |
18+
| --------------------- | ----------------------------------------------------------- | ---------------------------------------------------------------------------------- |
19+
| `clusters` | `autoware_perception_msgs::msg::DetectedObjectsWithFeature` | clustered pointcloud |
20+
| `input/camera_infoID` | `sensor_msgs::msg::CameraInfo` | camera information to project 3d points onto image planes, `ID` is between 0 and 7 |
21+
| `input/roisID` | `autoware_perception_msgs::msg::DetectedObjectsWithFeature` | ROIs from each image, `ID` is between 0 and 7 |
22+
| `input/image_rawID` | `sensor_msgs::msg::Image` | images for visualization, `ID` is between 0 and 7 |
23+
24+
### Output
25+
26+
| Name | Type | Description |
27+
| -------------------- | ------------------------- | ------------------------------------------------- |
28+
| `output/image_rawID` | `sensor_msgs::msg::Image` | images for visualization, `ID` is between 0 and 7 |
29+
30+
## Parameters
31+
32+
### Core Parameters
33+
34+
| Name | Type | Description |
35+
| --------------------------- | ----- | ----------------------------------------------------------------------------- |
36+
| `use_iou_x` | bool | calculate IoU only along x-axis |
37+
| `use_iou_y` | bool | calculate IoU only along y-axis |
38+
| `use_iou` | bool | calculate IoU both along x-axis and y-axis |
39+
| `use_cluster_semantic_type` | bool | if `false`, the labels of clusters are overwritten by `UNKNOWN` before fusion |
40+
| `iou_threshold` | float | the IoU threshold to overwrite a label of clusters with a label of roi |
41+
| `rois_number` | int | the number of input rois |
42+
43+
## Assumptions / Known limits
44+
45+
<!-- Write assumptions and limitations of your implementation.
46+
47+
Example:
48+
This algorithm assumes obstacles are not moving, so if they rapidly move after the vehicle started to avoid them, it might collide with them.
49+
Also, this algorithm doesn't care about blind spots. In general, since too close obstacles aren't visible due to the sensing performance limit, please take enough margin to obstacles.
50+
-->
51+
52+
## (Optional) Error detection and handling
53+
54+
<!-- Write how to detect errors and how to recover from them.
55+
56+
Example:
57+
This package can handle up to 20 obstacles. If more obstacles found, this node will give up and raise diagnostic errors.
58+
-->
59+
60+
## (Optional) Performance characterization
61+
62+
<!-- Write performance information like complexity. If it wouldn't be the bottleneck, not necessary.
63+
64+
Example:
65+
### Complexity
66+
67+
This algorithm is O(N).
68+
69+
### Processing time
70+
71+
...
72+
-->
73+
74+
## (Optional) References/External links
75+
76+
<!-- Write links you referred to when you implemented.
77+
78+
Example:
79+
[1] {link_to_a_thesis}
80+
[2] {link_to_an_issue}
81+
-->
82+
83+
## (Optional) Future extensions / Unimplemented parts
84+
85+
<!-- Write future extensions of this package.
86+
87+
Example:
88+
Currently, this package can't handle the chattering obstacles well. We plan to add some probabilistic filters in the perception layer to improve it.
89+
Also, there are some parameters that should be global(e.g. vehicle size, max steering, etc.). These will be refactored and defined as global parameters so that we can share the same parameters between different nodes.
90+
-->
Loading
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,135 @@
1+
// Copyright 2020 Tier IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef ROI_CLUSTER_FUSION__ROI_CLUSTER_FUSION_NODELET_HPP_
16+
#define ROI_CLUSTER_FUSION__ROI_CLUSTER_FUSION_NODELET_HPP_
17+
18+
#define EIGEN_MPL2_ONLY
19+
20+
#include <Eigen/Core>
21+
#include <image_transport/image_transport.hpp>
22+
#include <rclcpp/rclcpp.hpp>
23+
24+
#include <autoware_perception_msgs/msg/detected_objects_with_feature.hpp>
25+
#include <sensor_msgs/msg/camera_info.hpp>
26+
27+
#include <boost/circular_buffer.hpp>
28+
29+
#include <cv_bridge/cv_bridge.h>
30+
#include <message_filters/pass_through.h>
31+
#include <message_filters/subscriber.h>
32+
#include <message_filters/sync_policies/approximate_time.h>
33+
#include <message_filters/synchronizer.h>
34+
#include <tf2_ros/buffer.h>
35+
#include <tf2_ros/transform_listener.h>
36+
37+
#include <map>
38+
#include <memory>
39+
#include <vector>
40+
41+
namespace roi_cluster_fusion
42+
{
43+
class Debugger
44+
{
45+
public:
46+
explicit Debugger(rclcpp::Node * node, const int camera_num);
47+
~Debugger() = default;
48+
rclcpp::Node * node_;
49+
void showImage(
50+
const int id, const rclcpp::Time & time,
51+
const std::vector<sensor_msgs::msg::RegionOfInterest> & image_rois,
52+
const std::vector<sensor_msgs::msg::RegionOfInterest> & pointcloud_rois,
53+
const std::vector<Eigen::Vector2d> & points);
54+
55+
private:
56+
void imageCallback(const sensor_msgs::msg::Image::ConstSharedPtr & input_image_msg, const int id);
57+
std::shared_ptr<image_transport::ImageTransport> image_transport_;
58+
std::vector<image_transport::Subscriber> image_subs_;
59+
std::vector<image_transport::Publisher> image_pubs_;
60+
std::vector<boost::circular_buffer<sensor_msgs::msg::Image::ConstSharedPtr>> image_buffers_;
61+
};
62+
63+
class RoiClusterFusionNodelet : public rclcpp::Node
64+
{
65+
public:
66+
explicit RoiClusterFusionNodelet(const rclcpp::NodeOptions & options);
67+
68+
private:
69+
void fusionCallback(
70+
autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_cluster_msg,
71+
autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_roi0_msg,
72+
autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_roi1_msg,
73+
autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_roi2_msg,
74+
autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_roi3_msg,
75+
autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_roi4_msg,
76+
autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_roi5_msg,
77+
autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_roi6_msg,
78+
autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_roi7_msg);
79+
void cameraInfoCallback(
80+
const sensor_msgs::msg::CameraInfo::ConstSharedPtr input_camera_info_msg, const int id);
81+
double calcIoU(
82+
const sensor_msgs::msg::RegionOfInterest & roi_1,
83+
const sensor_msgs::msg::RegionOfInterest & roi_2);
84+
double calcIoUX(
85+
const sensor_msgs::msg::RegionOfInterest & roi_1,
86+
const sensor_msgs::msg::RegionOfInterest & roi_2);
87+
double calcIoUY(
88+
const sensor_msgs::msg::RegionOfInterest & roi_1,
89+
const sensor_msgs::msg::RegionOfInterest & roi_2);
90+
91+
rclcpp::Publisher<autoware_perception_msgs::msg::DetectedObjectsWithFeature>::SharedPtr
92+
labeled_cluster_pub_;
93+
std::vector<rclcpp::Subscription<sensor_msgs::msg::CameraInfo>::SharedPtr> v_camera_info_sub_;
94+
tf2_ros::Buffer tf_buffer_;
95+
tf2_ros::TransformListener tf_listener_ptr_;
96+
message_filters::Subscriber<autoware_perception_msgs::msg::DetectedObjectsWithFeature>
97+
cluster_sub_;
98+
std::vector<std::shared_ptr<
99+
message_filters::Subscriber<autoware_perception_msgs::msg::DetectedObjectsWithFeature>>>
100+
v_roi_sub_;
101+
message_filters::PassThrough<autoware_perception_msgs::msg::DetectedObjectsWithFeature>
102+
passthrough_;
103+
typedef message_filters::sync_policies::ApproximateTime<
104+
autoware_perception_msgs::msg::DetectedObjectsWithFeature,
105+
autoware_perception_msgs::msg::DetectedObjectsWithFeature,
106+
autoware_perception_msgs::msg::DetectedObjectsWithFeature,
107+
autoware_perception_msgs::msg::DetectedObjectsWithFeature,
108+
autoware_perception_msgs::msg::DetectedObjectsWithFeature,
109+
autoware_perception_msgs::msg::DetectedObjectsWithFeature,
110+
autoware_perception_msgs::msg::DetectedObjectsWithFeature,
111+
autoware_perception_msgs::msg::DetectedObjectsWithFeature,
112+
autoware_perception_msgs::msg::DetectedObjectsWithFeature>
113+
SyncPolicy;
114+
typedef message_filters::Synchronizer<SyncPolicy> Sync;
115+
std::shared_ptr<Sync> sync_ptr_;
116+
inline void dummyCallback(
117+
autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input)
118+
{
119+
auto dummy = input;
120+
passthrough_.add(dummy);
121+
}
122+
// ROS Parameters
123+
bool use_iou_x_;
124+
bool use_iou_y_;
125+
bool use_iou_;
126+
bool use_cluster_semantic_type_;
127+
double iou_threshold_;
128+
int rois_number_;
129+
std::map<int, sensor_msgs::msg::CameraInfo> m_camera_info_;
130+
std::shared_ptr<Debugger> debugger_;
131+
};
132+
133+
} // namespace roi_cluster_fusion
134+
135+
#endif // ROI_CLUSTER_FUSION__ROI_CLUSTER_FUSION_NODELET_HPP_
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,75 @@
1+
<launch>
2+
<arg name="input/rois_number" default="1"/>
3+
<arg name="input/rois0" default="rois0"/>
4+
<arg name="input/camera_info0" default="/camera_info0"/>
5+
<arg name="input/rois1" default="rois1"/>
6+
<arg name="input/camera_info1" default="/camera_info1"/>
7+
<arg name="input/rois2" default="rois2"/>
8+
<arg name="input/camera_info2" default="/camera_info2"/>
9+
<arg name="input/rois3" default="rois3"/>
10+
<arg name="input/camera_info3" default="/camera_info3"/>
11+
<arg name="input/rois4" default="rois4"/>
12+
<arg name="input/camera_info4" default="/camera_info4"/>
13+
<arg name="input/rois5" default="rois5"/>
14+
<arg name="input/camera_info5" default="/camera_info5"/>
15+
<arg name="input/rois6" default="rois6"/>
16+
<arg name="input/camera_info6" default="/camera_info6"/>
17+
<arg name="input/rois7" default="rois7"/>
18+
<arg name="input/camera_info7" default="/camera_info7"/>
19+
<arg name="input/clusters" default="clusters"/>
20+
<arg name="output" default="labeled_clusters"/>
21+
22+
<!-- for eval variable-->
23+
<arg name="input_rois_number" default="$(var input/rois_number)"/>
24+
25+
<!-- debug -->
26+
<arg name="debug_mode" default="false"/>
27+
<arg name="input/image0" default="/image_raw0"/>
28+
<arg name="input/image1" default="/image_raw1"/>
29+
<arg name="input/image2" default="/image_raw2"/>
30+
<arg name="input/image3" default="/image_raw3"/>
31+
<arg name="input/image4" default="/image_raw4"/>
32+
<arg name="input/image5" default="/image_raw5"/>
33+
<arg name="input/image6" default="/image_raw6"/>
34+
<arg name="input/image7" default="/image_raw7"/>
35+
<group>
36+
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '1' &quot;)" from="input/rois0" to="$(var input/rois0)"/>
37+
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '1' &quot;)" from="input/camera_info0" to="$(var input/camera_info0)"/>
38+
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '2' &quot;)" from="input/rois1" to="$(var input/rois1)"/>
39+
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '2' &quot;)" from="input/camera_info1" to="$(var input/camera_info1)"/>
40+
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '3' &quot;)" from="input/rois2" to="$(var input/rois2)"/>
41+
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '3' &quot;)" from="input/camera_info2" to="$(var input/camera_info2)"/>
42+
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '4' &quot;)" from="input/rois3" to="$(var input/rois3)"/>
43+
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '4' &quot;)" from="input/camera_info3" to="$(var input/camera_info3)"/>
44+
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '5' &quot;)" from="input/rois4" to="$(var input/rois4)"/>
45+
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '5' &quot;)" from="input/camera_info4" to="$(var input/camera_info4)"/>
46+
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '6' &quot;)" from="input/rois5" to="$(var input/rois5)"/>
47+
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '6' &quot;)" from="input/camera_info5" to="$(var input/camera_info5)"/>
48+
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '7' &quot;)" from="input/rois6" to="$(var input/rois6)"/>
49+
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '7' &quot;)" from="input/camera_info6" to="$(var input/camera_info6)"/>
50+
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '8' &quot;)" from="input/rois7" to="$(var input/rois7)"/>
51+
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '8' &quot;)" from="input/camera_info7" to="$(var input/camera_info7)"/>
52+
53+
<set_remap if="$(eval &quot; '$(var input_rois_number)' >= '1' &quot;)" from="input/image_raw0" to="$(var input/image0)"/>
54+
<set_remap if="$(eval &quot; '$(var input_rois_number)' >= '2' &quot;)" from="input/image_raw1" to="$(var input/image1)"/>
55+
<set_remap if="$(eval &quot; '$(var input_rois_number)' >= '3' &quot;)" from="input/image_raw2" to="$(var input/image2)"/>
56+
<set_remap if="$(eval &quot; '$(var input_rois_number)' >= '4' &quot;)" from="input/image_raw3" to="$(var input/image3)"/>
57+
<set_remap if="$(eval &quot; '$(var input_rois_number)' >= '5' &quot;)" from="input/image_raw4" to="$(var input/image4)"/>
58+
<set_remap if="$(eval &quot; '$(var input_rois_number)' >= '6' &quot;)" from="input/image_raw5" to="$(var input/image5)"/>
59+
<set_remap if="$(eval &quot; '$(var input_rois_number)' >= '7' &quot;)" from="input/image_raw6" to="$(var input/image6)"/>
60+
<set_remap if="$(eval &quot; '$(var input_rois_number)' >= '8' &quot;)" from="input/image_raw7" to="$(var input/image7)"/>
61+
62+
<node pkg="roi_cluster_fusion" exec="roi_cluster_fusion_node" name="roi_cluster_fusion">
63+
<param name="use_iou" value="true"/>
64+
<param name="use_iou_x" value="false"/>
65+
<param name="use_iou_y" value="false"/>
66+
<param name="iou_threshold" value="0.35"/>
67+
<remap from="clusters" to="$(var input/clusters)"/>
68+
<remap from="output/labeled_clusters" to="$(var output)"/>
69+
<param name="rois_number" value="$(var input/rois_number)" />
70+
71+
<!-- debug -->
72+
<param name="debug_mode" value="$(var debug_mode)"/>
73+
</node>
74+
</group>
75+
</launch>
+32
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,32 @@
1+
<?xml version="1.0"?>
2+
<package format="2">
3+
<name>roi_cluster_fusion</name>
4+
<version>0.1.0</version>
5+
<description>The roi_cluster_fusion package</description>
6+
7+
<maintainer email="yukihiro.saito@tier4.jp">Yukihiro Saito</maintainer>
8+
<license>Apache License 2.0</license>
9+
10+
<buildtool_depend>ament_cmake_auto</buildtool_depend>
11+
<depend>autoware_perception_msgs</depend>
12+
<depend>cv_bridge</depend>
13+
<depend>image_transport</depend>
14+
<depend>message_filters</depend>
15+
<depend>pcl_conversions</depend>
16+
<depend>pcl_ros</depend>
17+
<depend>rclcpp</depend>
18+
<depend>rclcpp_components</depend>
19+
<depend>sensor_msgs</depend>
20+
<depend>tf2</depend>
21+
<depend>tf2_ros</depend>
22+
<depend>tf2_sensor_msgs</depend>
23+
24+
<!-- The export tag contains other, unspecified, tags -->
25+
26+
<test_depend>ament_lint_auto</test_depend>
27+
<test_depend>autoware_lint_common</test_depend>
28+
29+
<export>
30+
<build_type>ament_cmake</build_type>
31+
</export>
32+
</package>

‎perception/roi_cluster_fusion/src/roi_cluster_fusion_nodelet.cpp

+511
Large diffs are not rendered by default.

0 commit comments

Comments
 (0)
Please sign in to comment.