detection_class_remapper.cpp 2.9 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071
  1. // Copyright 2024 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. #include <detection_class_remapper.hpp>
  15. namespace autoware::lidar_transfusion
  16. {
  17. void DetectionClassRemapper::setParameters(
  18. const std::vector<int64_t> & allow_remapping_by_area_matrix,
  19. const std::vector<double> & min_area_matrix, const std::vector<double> & max_area_matrix)
  20. {
  21. assert(allow_remapping_by_area_matrix.size() == min_area_matrix.size());
  22. assert(allow_remapping_by_area_matrix.size() == max_area_matrix.size());
  23. assert(
  24. std::pow(static_cast<int>(std::sqrt(min_area_matrix.size())), 2) == min_area_matrix.size());
  25. num_labels_ = static_cast<int>(std::sqrt(min_area_matrix.size()));
  26. Eigen::Map<const Eigen::Matrix<int64_t, Eigen::Dynamic, Eigen::Dynamic>>
  27. allow_remapping_by_area_matrix_tmp(
  28. allow_remapping_by_area_matrix.data(), num_labels_, num_labels_);
  29. allow_remapping_by_area_matrix_ = allow_remapping_by_area_matrix_tmp.transpose()
  30. .cast<bool>(); // Eigen is column major by default
  31. Eigen::Map<const Eigen::MatrixXd> min_area_matrix_tmp(
  32. min_area_matrix.data(), num_labels_, num_labels_);
  33. min_area_matrix_ = min_area_matrix_tmp.transpose(); // Eigen is column major by default
  34. Eigen::Map<const Eigen::MatrixXd> max_area_matrix_tmp(
  35. max_area_matrix.data(), num_labels_, num_labels_);
  36. max_area_matrix_ = max_area_matrix_tmp.transpose(); // Eigen is column major by default
  37. min_area_matrix_ = min_area_matrix_.unaryExpr(
  38. [](double v) { return std::isfinite(v) ? v : std::numeric_limits<double>::max(); });
  39. max_area_matrix_ = max_area_matrix_.unaryExpr(
  40. [](double v) { return std::isfinite(v) ? v : std::numeric_limits<double>::max(); });
  41. }
  42. //void DetectionClassRemapper::mapClasses(autoware_perception_msgs::msg::DetectedObjects & msg)
  43. //{
  44. // for (auto & object : msg.objects) {
  45. // const float bev_area = object.shape.dimensions.x * object.shape.dimensions.y;
  46. // for (auto & classification : object.classification) {
  47. // auto & label = classification.label;
  48. // for (int i = 0; i < num_labels_; ++i) {
  49. // if (
  50. // allow_remapping_by_area_matrix_(label, i) && bev_area >= min_area_matrix_(label, i) &&
  51. // bev_area <= max_area_matrix_(label, i)) {
  52. // label = i;
  53. // break;
  54. // }
  55. // }
  56. // }
  57. // }
  58. //}
  59. } // namespace autoware::lidar_transfusion