Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Dec 11, 2024
1 parent 5749585 commit 0d53748
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -185,7 +185,8 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options)

// Declare parameters
config.tracker_lifetime = declare_parameter<double>("tracker_lifetime", 1.0);
config.min_known_object_removal_iou = declare_parameter<double>("min_known_object_removal_iou", 0.1);
config.min_known_object_removal_iou =
declare_parameter<double>("min_known_object_removal_iou", 0.1);
config.min_unknown_object_removal_iou =
declare_parameter<double>("min_unknown_object_removal_iou", 0.05);
config.distance_threshold = declare_parameter<double>("distance_threshold", 5.0);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,8 @@ std::shared_ptr<Tracker> TrackerProcessor::createNewTracker(
const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time,
const geometry_msgs::msg::Transform & self_transform, const uint & channel_index) const
{
const LabelType label = autoware::object_recognition_utils::getHighestProbLabel(object.classification);
const LabelType label =
autoware::object_recognition_utils::getHighestProbLabel(object.classification);
if (config_.tracker_map.count(label) != 0) {
const auto tracker = config_.tracker_map.at(label);
if (tracker == "bicycle_tracker")
Expand Down Expand Up @@ -161,7 +162,8 @@ void TrackerProcessor::removeOverlappedTracker(const rclcpp::Time & time)

// Check the Intersection over Union (IoU) between the two objects
const double min_union_iou_area = 1e-2;
const auto iou = autoware::object_recognition_utils::get2dIoU(object1, object2, min_union_iou_area);
const auto iou =
autoware::object_recognition_utils::get2dIoU(object1, object2, min_union_iou_area);
const auto & label1 = (*itr1)->getHighestProbLabel();
const auto & label2 = (*itr2)->getHighestProbLabel();
bool should_delete_tracker1 = false;
Expand Down

0 comments on commit 0d53748

Please sign in to comment.