Skip to content

Commit

Permalink
fix: update parameter value (autowarefoundation#4955)
Browse files Browse the repository at this point in the history
Signed-off-by: ktro2828 <[email protected]>
  • Loading branch information
ktro2828 authored Sep 12, 2023
1 parent 57b1ef1 commit 64ed461
Show file tree
Hide file tree
Showing 3 changed files with 16 additions and 15 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -43,13 +43,13 @@ class RoiClusterFusionNode
bool use_iou_{false};
bool use_cluster_semantic_type_{false};
bool only_allow_inside_cluster_{false};
float roi_scale_factor_{1.1f};
float iou_threshold_{0.0f};
float unknown_iou_threshold_{0.0f};
double roi_scale_factor_{1.1};
double iou_threshold_{0.0};
double unknown_iou_threshold_{0.0};
const float min_roi_existence_prob_ =
0.1; // keep small value to lessen affect on merger object stage
bool remove_unknown_;
float trust_distance_;
double trust_distance_;

bool filter_by_distance(const DetectedObjectWithFeature & obj);
bool out_of_scope(const DetectedObjectWithFeature & obj);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,9 +48,10 @@
<param name="use_iou" value="true"/>
<param name="use_iou_x" value="false"/>
<param name="use_iou_y" value="false"/>
<param name="use_cluster_semantic_type" 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="iou_threshold" value="0.65"/>
<param name="unknown_iou_threshold" value="0.1"/>
<param name="rois_number" value="$(var input/rois_number)"/>
<param name="remove_unknown" value="$(var remove_unknown)"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,16 +36,16 @@ namespace image_projection_based_fusion
RoiClusterFusionNode::RoiClusterFusionNode(const rclcpp::NodeOptions & options)
: FusionNode<DetectedObjectsWithFeature, DetectedObjectWithFeature>("roi_cluster_fusion", options)
{
use_iou_x_ = declare_parameter("use_iou_x", true);
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_", true);
roi_scale_factor_ = declare_parameter("roi_scale_factor", 1.1);
iou_threshold_ = declare_parameter("iou_threshold", 0.1);
unknown_iou_threshold_ = declare_parameter("unknown_iou_threshold", 0.1);
remove_unknown_ = declare_parameter("remove_unknown", false);
trust_distance_ = declare_parameter("trust_distance", 100.0);
use_iou_x_ = declare_parameter<bool>("use_iou_x");
use_iou_y_ = declare_parameter<bool>("use_iou_y");
use_iou_ = declare_parameter<bool>("use_iou");
use_cluster_semantic_type_ = declare_parameter<bool>("use_cluster_semantic_type");
only_allow_inside_cluster_ = declare_parameter<bool>("only_allow_inside_cluster");
roi_scale_factor_ = declare_parameter<double>("roi_scale_factor");
iou_threshold_ = declare_parameter<double>("iou_threshold");
unknown_iou_threshold_ = declare_parameter<double>("unknown_iou_threshold");
remove_unknown_ = declare_parameter<bool>("remove_unknown");
trust_distance_ = declare_parameter<double>("trust_distance");
}

void RoiClusterFusionNode::preprocess(DetectedObjectsWithFeature & output_cluster_msg)
Expand Down

0 comments on commit 64ed461

Please sign in to comment.