Skip to content

Commit

Permalink
feat(roi_cluster_fusion): update default value of `only_allow_inside_…
Browse files Browse the repository at this point in the history
…cluster` is `true` (autowarefoundation#4212)

Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp>
  • Loading branch information
ktro2828 authored Jul 10, 2023
1 parent d4bb8bd commit 5605b19
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@
<param name="use_iou" value="true"/>
<param name="use_iou_x" value="false"/>
<param name="use_iou_y" value="false"/>
<param name="only_allow_inside_cluster" value="false"/>
<param name="only_allow_inside_cluster" value="true"/>
<param name="roi_scale_factor" value="1.1"/>
<param name="iou_threshold" value="0.35"/>
<param name="rois_number" value="$(var input/rois_number)"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ RoiClusterFusionNode::RoiClusterFusionNode(const rclcpp::NodeOptions & options)
use_iou_y_ = declare_parameter("use_iou_y", false);
use_iou_ = declare_parameter("use_iou", false);
use_cluster_semantic_type_ = declare_parameter("use_cluster_semantic_type", false);
only_allow_inside_cluster_ = declare_parameter("only_allow_inside_cluster_", false);
only_allow_inside_cluster_ = declare_parameter("only_allow_inside_cluster_", true);
roi_scale_factor_ = declare_parameter("roi_scale_factor", 1.1);
iou_threshold_ = declare_parameter("iou_threshold", 0.1);
remove_unknown_ = declare_parameter("remove_unknown", false);
Expand Down

0 comments on commit 5605b19

Please sign in to comment.