Skip to content

Commit

Permalink
feat: add roi cluster fusion package (#116)
Browse files Browse the repository at this point in the history
* release v0.4.0

* Modify to use projection matrix with undistorted 2D result (#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 (#28)

* Rename h files to hpp (#142)

* Change includes

* Rename files

* Adjustments to make things compile

* Other packages

* Adjust copyright notice on 532 out of 699 source files (#143)

* Use quotes for includes where appropriate (#144)

* Use quotes for includes where appropriate

* Fix lint tests

* Make tests pass hopefully

* ported roi_cluster_fusion from ROS1 to ROS2 (#118)

compiles succesfully.
Getting some undefined reference error while launching the node.

* Port euclidean cluster (#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 (#239)

* Fix perception launches (#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 (#321)

* restore v0.5.0

* Feature/fusion debug (#1051)

* add debuger

* change param

* add publisher

* Compatible with opencv4 (#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 (#346)

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* Fix transform (#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 (#440)

* add use_sim-time option (#454)

* Format launch files (#1219)

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

* Unify Apache-2.0 license name (#1242)

* Remove use_sim_time for set_parameter (#1260)

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* Add pre-commit (#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 (#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 (#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 (#1624)

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* fix typo & check debugger (#1511) (#1625)

Co-authored-by: Yusuke Muramatsu <yukke42@users.noreply.github.com>

* Use set_remap for if tag (#1800)

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* Apply format (#1999)

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

Fix cpplint

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

* Detection by tracker (#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 (#2219)

* Fix qos in roi cluster fusion (#2218)

* fix confidence (#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 (#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 (#500)

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

* port roi cluster fusion (#536)

* remove COLCON_IGNORE

* use DetectedObjectsWithFeature

* fix topic type

* update overwrite condition

* add README of roi_cluster_fusion (#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>
  • Loading branch information
21 people committed Dec 6, 2021
1 parent 7dd097d commit a575a9e
Show file tree
Hide file tree
Showing 7 changed files with 887 additions and 0 deletions.
44 changes: 44 additions & 0 deletions perception/roi_cluster_fusion/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
cmake_minimum_required(VERSION 3.5)
project(roi_cluster_fusion)

if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()


find_package(ament_lint_auto REQUIRED)
find_package(ament_cmake_auto REQUIRED)
find_package(OpenCV REQUIRED)
find_package(Eigen3 REQUIRED)

ament_auto_find_build_dependencies()


include_directories(
include
${OpenCV_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIR}
)

ament_auto_add_library(roi_cluster_fusion_nodelet SHARED src/roi_cluster_fusion_nodelet.cpp)
target_link_libraries(roi_cluster_fusion_nodelet
${OpenCV_LIBRARIES}
${EIGEN3_LIBRARIES}
)

rclcpp_components_register_node(roi_cluster_fusion_nodelet
PLUGIN "roi_cluster_fusion::RoiClusterFusionNodelet"
EXECUTABLE roi_cluster_fusion_node
)

ament_auto_package(INSTALL_TO_SHARE
launch
)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
endif()
90 changes: 90 additions & 0 deletions perception/roi_cluster_fusion/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,90 @@
# roi_cluster_fusion

## Purpose

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.

## Inner-workings / Algorithms

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.

![roi_cluster_fusion_image](./images/roi_cluster_fusion.png)

## Inputs / Outputs

### Input

| Name | Type | Description |
| --------------------- | ----------------------------------------------------------- | ---------------------------------------------------------------------------------- |
| `clusters` | `autoware_perception_msgs::msg::DetectedObjectsWithFeature` | clustered pointcloud |
| `input/camera_infoID` | `sensor_msgs::msg::CameraInfo` | camera information to project 3d points onto image planes, `ID` is between 0 and 7 |
| `input/roisID` | `autoware_perception_msgs::msg::DetectedObjectsWithFeature` | ROIs from each image, `ID` is between 0 and 7 |
| `input/image_rawID` | `sensor_msgs::msg::Image` | images for visualization, `ID` is between 0 and 7 |

### Output

| Name | Type | Description |
| -------------------- | ------------------------- | ------------------------------------------------- |
| `output/image_rawID` | `sensor_msgs::msg::Image` | images for visualization, `ID` is between 0 and 7 |

## Parameters

### Core Parameters

| Name | Type | Description |
| --------------------------- | ----- | ----------------------------------------------------------------------------- |
| `use_iou_x` | bool | calculate IoU only along x-axis |
| `use_iou_y` | bool | calculate IoU only along y-axis |
| `use_iou` | bool | calculate IoU both along x-axis and y-axis |
| `use_cluster_semantic_type` | bool | if `false`, the labels of clusters are overwritten by `UNKNOWN` before fusion |
| `iou_threshold` | float | the IoU threshold to overwrite a label of clusters with a label of roi |
| `rois_number` | int | the number of input rois |

## Assumptions / Known limits

<!-- Write assumptions and limitations of your implementation.
Example:
This algorithm assumes obstacles are not moving, so if they rapidly move after the vehicle started to avoid them, it might collide with them.
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.
-->

## (Optional) Error detection and handling

<!-- Write how to detect errors and how to recover from them.
Example:
This package can handle up to 20 obstacles. If more obstacles found, this node will give up and raise diagnostic errors.
-->

## (Optional) Performance characterization

<!-- Write performance information like complexity. If it wouldn't be the bottleneck, not necessary.
Example:
### Complexity
This algorithm is O(N).
### Processing time
...
-->

## (Optional) References/External links

<!-- Write links you referred to when you implemented.
Example:
[1] {link_to_a_thesis}
[2] {link_to_an_issue}
-->

## (Optional) Future extensions / Unimplemented parts

<!-- Write future extensions of this package.
Example:
Currently, this package can't handle the chattering obstacles well. We plan to add some probabilistic filters in the perception layer to improve it.
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.
-->
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Original file line number Diff line number Diff line change
@@ -0,0 +1,135 @@
// Copyright 2020 Tier IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef ROI_CLUSTER_FUSION__ROI_CLUSTER_FUSION_NODELET_HPP_
#define ROI_CLUSTER_FUSION__ROI_CLUSTER_FUSION_NODELET_HPP_

#define EIGEN_MPL2_ONLY

#include <Eigen/Core>
#include <image_transport/image_transport.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_perception_msgs/msg/detected_objects_with_feature.hpp>
#include <sensor_msgs/msg/camera_info.hpp>

#include <boost/circular_buffer.hpp>

#include <cv_bridge/cv_bridge.h>
#include <message_filters/pass_through.h>
#include <message_filters/subscriber.h>
#include <message_filters/sync_policies/approximate_time.h>
#include <message_filters/synchronizer.h>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>

#include <map>
#include <memory>
#include <vector>

namespace roi_cluster_fusion
{
class Debugger
{
public:
explicit Debugger(rclcpp::Node * node, const int camera_num);
~Debugger() = default;
rclcpp::Node * node_;
void showImage(
const int id, const rclcpp::Time & time,
const std::vector<sensor_msgs::msg::RegionOfInterest> & image_rois,
const std::vector<sensor_msgs::msg::RegionOfInterest> & pointcloud_rois,
const std::vector<Eigen::Vector2d> & points);

private:
void imageCallback(const sensor_msgs::msg::Image::ConstSharedPtr & input_image_msg, const int id);
std::shared_ptr<image_transport::ImageTransport> image_transport_;
std::vector<image_transport::Subscriber> image_subs_;
std::vector<image_transport::Publisher> image_pubs_;
std::vector<boost::circular_buffer<sensor_msgs::msg::Image::ConstSharedPtr>> image_buffers_;
};

class RoiClusterFusionNodelet : public rclcpp::Node
{
public:
explicit RoiClusterFusionNodelet(const rclcpp::NodeOptions & options);

private:
void fusionCallback(
autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_cluster_msg,
autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_roi0_msg,
autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_roi1_msg,
autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_roi2_msg,
autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_roi3_msg,
autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_roi4_msg,
autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_roi5_msg,
autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_roi6_msg,
autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_roi7_msg);
void cameraInfoCallback(
const sensor_msgs::msg::CameraInfo::ConstSharedPtr input_camera_info_msg, const int id);
double calcIoU(
const sensor_msgs::msg::RegionOfInterest & roi_1,
const sensor_msgs::msg::RegionOfInterest & roi_2);
double calcIoUX(
const sensor_msgs::msg::RegionOfInterest & roi_1,
const sensor_msgs::msg::RegionOfInterest & roi_2);
double calcIoUY(
const sensor_msgs::msg::RegionOfInterest & roi_1,
const sensor_msgs::msg::RegionOfInterest & roi_2);

rclcpp::Publisher<autoware_perception_msgs::msg::DetectedObjectsWithFeature>::SharedPtr
labeled_cluster_pub_;
std::vector<rclcpp::Subscription<sensor_msgs::msg::CameraInfo>::SharedPtr> v_camera_info_sub_;
tf2_ros::Buffer tf_buffer_;
tf2_ros::TransformListener tf_listener_ptr_;
message_filters::Subscriber<autoware_perception_msgs::msg::DetectedObjectsWithFeature>
cluster_sub_;
std::vector<std::shared_ptr<
message_filters::Subscriber<autoware_perception_msgs::msg::DetectedObjectsWithFeature>>>
v_roi_sub_;
message_filters::PassThrough<autoware_perception_msgs::msg::DetectedObjectsWithFeature>
passthrough_;
typedef message_filters::sync_policies::ApproximateTime<
autoware_perception_msgs::msg::DetectedObjectsWithFeature,
autoware_perception_msgs::msg::DetectedObjectsWithFeature,
autoware_perception_msgs::msg::DetectedObjectsWithFeature,
autoware_perception_msgs::msg::DetectedObjectsWithFeature,
autoware_perception_msgs::msg::DetectedObjectsWithFeature,
autoware_perception_msgs::msg::DetectedObjectsWithFeature,
autoware_perception_msgs::msg::DetectedObjectsWithFeature,
autoware_perception_msgs::msg::DetectedObjectsWithFeature,
autoware_perception_msgs::msg::DetectedObjectsWithFeature>
SyncPolicy;
typedef message_filters::Synchronizer<SyncPolicy> Sync;
std::shared_ptr<Sync> sync_ptr_;
inline void dummyCallback(
autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input)
{
auto dummy = input;
passthrough_.add(dummy);
}
// ROS Parameters
bool use_iou_x_;
bool use_iou_y_;
bool use_iou_;
bool use_cluster_semantic_type_;
double iou_threshold_;
int rois_number_;
std::map<int, sensor_msgs::msg::CameraInfo> m_camera_info_;
std::shared_ptr<Debugger> debugger_;
};

} // namespace roi_cluster_fusion

#endif // ROI_CLUSTER_FUSION__ROI_CLUSTER_FUSION_NODELET_HPP_
75 changes: 75 additions & 0 deletions perception/roi_cluster_fusion/launch/roi_cluster_fusion.launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,75 @@
<launch>
<arg name="input/rois_number" default="1"/>
<arg name="input/rois0" default="rois0"/>
<arg name="input/camera_info0" default="/camera_info0"/>
<arg name="input/rois1" default="rois1"/>
<arg name="input/camera_info1" default="/camera_info1"/>
<arg name="input/rois2" default="rois2"/>
<arg name="input/camera_info2" default="/camera_info2"/>
<arg name="input/rois3" default="rois3"/>
<arg name="input/camera_info3" default="/camera_info3"/>
<arg name="input/rois4" default="rois4"/>
<arg name="input/camera_info4" default="/camera_info4"/>
<arg name="input/rois5" default="rois5"/>
<arg name="input/camera_info5" default="/camera_info5"/>
<arg name="input/rois6" default="rois6"/>
<arg name="input/camera_info6" default="/camera_info6"/>
<arg name="input/rois7" default="rois7"/>
<arg name="input/camera_info7" default="/camera_info7"/>
<arg name="input/clusters" default="clusters"/>
<arg name="output" default="labeled_clusters"/>

<!-- for eval variable-->
<arg name="input_rois_number" default="$(var input/rois_number)"/>

<!-- debug -->
<arg name="debug_mode" default="false"/>
<arg name="input/image0" default="/image_raw0"/>
<arg name="input/image1" default="/image_raw1"/>
<arg name="input/image2" default="/image_raw2"/>
<arg name="input/image3" default="/image_raw3"/>
<arg name="input/image4" default="/image_raw4"/>
<arg name="input/image5" default="/image_raw5"/>
<arg name="input/image6" default="/image_raw6"/>
<arg name="input/image7" default="/image_raw7"/>
<group>
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '1' &quot;)" from="input/rois0" to="$(var input/rois0)"/>
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '1' &quot;)" from="input/camera_info0" to="$(var input/camera_info0)"/>
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '2' &quot;)" from="input/rois1" to="$(var input/rois1)"/>
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '2' &quot;)" from="input/camera_info1" to="$(var input/camera_info1)"/>
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '3' &quot;)" from="input/rois2" to="$(var input/rois2)"/>
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '3' &quot;)" from="input/camera_info2" to="$(var input/camera_info2)"/>
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '4' &quot;)" from="input/rois3" to="$(var input/rois3)"/>
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '4' &quot;)" from="input/camera_info3" to="$(var input/camera_info3)"/>
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '5' &quot;)" from="input/rois4" to="$(var input/rois4)"/>
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '5' &quot;)" from="input/camera_info4" to="$(var input/camera_info4)"/>
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '6' &quot;)" from="input/rois5" to="$(var input/rois5)"/>
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '6' &quot;)" from="input/camera_info5" to="$(var input/camera_info5)"/>
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '7' &quot;)" from="input/rois6" to="$(var input/rois6)"/>
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '7' &quot;)" from="input/camera_info6" to="$(var input/camera_info6)"/>
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '8' &quot;)" from="input/rois7" to="$(var input/rois7)"/>
<set_remap if="$(eval &quot;'$(var input_rois_number)' >= '8' &quot;)" from="input/camera_info7" to="$(var input/camera_info7)"/>

<set_remap if="$(eval &quot; '$(var input_rois_number)' >= '1' &quot;)" from="input/image_raw0" to="$(var input/image0)"/>
<set_remap if="$(eval &quot; '$(var input_rois_number)' >= '2' &quot;)" from="input/image_raw1" to="$(var input/image1)"/>
<set_remap if="$(eval &quot; '$(var input_rois_number)' >= '3' &quot;)" from="input/image_raw2" to="$(var input/image2)"/>
<set_remap if="$(eval &quot; '$(var input_rois_number)' >= '4' &quot;)" from="input/image_raw3" to="$(var input/image3)"/>
<set_remap if="$(eval &quot; '$(var input_rois_number)' >= '5' &quot;)" from="input/image_raw4" to="$(var input/image4)"/>
<set_remap if="$(eval &quot; '$(var input_rois_number)' >= '6' &quot;)" from="input/image_raw5" to="$(var input/image5)"/>
<set_remap if="$(eval &quot; '$(var input_rois_number)' >= '7' &quot;)" from="input/image_raw6" to="$(var input/image6)"/>
<set_remap if="$(eval &quot; '$(var input_rois_number)' >= '8' &quot;)" from="input/image_raw7" to="$(var input/image7)"/>

<node pkg="roi_cluster_fusion" exec="roi_cluster_fusion_node" name="roi_cluster_fusion">
<param name="use_iou" value="true"/>
<param name="use_iou_x" value="false"/>
<param name="use_iou_y" value="false"/>
<param name="iou_threshold" value="0.35"/>
<remap from="clusters" to="$(var input/clusters)"/>
<remap from="output/labeled_clusters" to="$(var output)"/>
<param name="rois_number" value="$(var input/rois_number)" />

<!-- debug -->
<param name="debug_mode" value="$(var debug_mode)"/>
</node>
</group>
</launch>
32 changes: 32 additions & 0 deletions perception/roi_cluster_fusion/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
<?xml version="1.0"?>
<package format="2">
<name>roi_cluster_fusion</name>
<version>0.1.0</version>
<description>The roi_cluster_fusion package</description>

<maintainer email="yukihiro.saito@tier4.jp">Yukihiro Saito</maintainer>
<license>Apache License 2.0</license>

<buildtool_depend>ament_cmake_auto</buildtool_depend>
<depend>autoware_perception_msgs</depend>
<depend>cv_bridge</depend>
<depend>image_transport</depend>
<depend>message_filters</depend>
<depend>pcl_conversions</depend>
<depend>pcl_ros</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>sensor_msgs</depend>
<depend>tf2</depend>
<depend>tf2_ros</depend>
<depend>tf2_sensor_msgs</depend>

<!-- The export tag contains other, unspecified, tags -->

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
Loading

0 comments on commit a575a9e

Please sign in to comment.