|
| 1 | +// |
| 2 | +// Created by shapelim on 22. 10. 23. |
| 3 | +// |
| 4 | + |
| 5 | +#ifndef PATCHWORK_ZONE_MODEL_HPP |
| 6 | +#define PATCHWORK_ZONE_MODEL_HPP |
| 7 | + |
| 8 | +#include <iostream> |
| 9 | +#include <vector> |
| 10 | +#include "patchwork/sensor_configs.hpp" |
| 11 | +#include "sensor_configs.hpp" |
| 12 | + |
| 13 | +#define INVALID_RING_IDX -1 |
| 14 | +#define OVERFLOWED_IDX -2 |
| 15 | + |
| 16 | +class ZoneModel { |
| 17 | + public: |
| 18 | + |
| 19 | + ZoneModel() {} |
| 20 | + |
| 21 | + ~ZoneModel() {} |
| 22 | + |
| 23 | + SensorConfig sensor_config_; |
| 24 | + |
| 25 | + /* |
| 26 | + * Common functions |
| 27 | + */ |
| 28 | + inline size_t size() const; |
| 29 | + // Important! 'virtual' is necessary to be declared in the base class |
| 30 | + // + the functions must be declared, i.e. {} is needed |
| 31 | + virtual void set_parameters() {} |
| 32 | + |
| 33 | +// |
| 34 | +// template<typename T> |
| 35 | +// int loadCloud(size_t idx, pcl::PointCloud<T> &cloud) const {} |
| 36 | +// |
| 37 | +// virtual void getGTLabeledScan(size_t i, pcl::PointCloud<pcl::PointXYZI>& cloud) {} |
| 38 | +// |
| 39 | +// // Estimated labels are added |
| 40 | +// virtual void getScanAndPose(size_t i, pcl::PointCloud<pcl::PointXYZI>& cloud, Eigen::Matrix4f &pose) { |
| 41 | +// cout << "[DefaultLoader] Default getScanandPose is Loaded" << endl; |
| 42 | +// } |
| 43 | +// |
| 44 | +// virtual void loadEstGroundAndInstanceLabels(const int i, std::vector<uint32_t>& ground_label, |
| 45 | +// std::vector<uint32_t>& instance_label) {} |
| 46 | +// |
| 47 | +// virtual void assignLabels(const std::vector<uint32_t> ground_labels, const std::vector<uint32_t> instance_labels, |
| 48 | +// const float min_z_voi, const float max_z_voi, |
| 49 | +// pcl::PointCloud<pcl::PointXYZI>& src_cloud, uint32_t& max_instance) {} |
| 50 | +// |
| 51 | +// virtual void testInheritance() { cout << "Test inheritance" << endl; } |
| 52 | + |
| 53 | +}; |
| 54 | + |
| 55 | +class ConcentricZoneModel : public ZoneModel { |
| 56 | + public: |
| 57 | + EIGEN_MAKE_ALIGNED_OPERATOR_NEW |
| 58 | + ConcentricZoneModel() {} |
| 59 | + |
| 60 | + ConcentricZoneModel(const std::string &sensor_model, const double sensor_height, |
| 61 | + const float min_range, const float max_range) { |
| 62 | + sensor_config_ = SensorConfig(sensor_model); |
| 63 | + num_zones_ = sensor_config_.num_laser_channels_per_zone_.size(); |
| 64 | + max_ring_index_in_first_zone = sensor_config_.num_laser_channels_per_zone_[0].size(); |
| 65 | + |
| 66 | + sensor_height_ = sensor_height; |
| 67 | + min_range_ = min_range; |
| 68 | + max_range_ = max_range; |
| 69 | + |
| 70 | + sqr_min_range_ = min_range * min_range; |
| 71 | + sqr_max_range_ = max_range * max_range; |
| 72 | + |
| 73 | + set_concentric_zone_model(); |
| 74 | + } |
| 75 | + bool is_range_boundary_set_; |
| 76 | + size_t max_ring_index_in_first_zone; |
| 77 | + size_t num_zones_; |
| 78 | + size_t num_total_rings_; |
| 79 | + double sensor_height_; |
| 80 | + float min_range_; |
| 81 | + float max_range_; |
| 82 | + float sqr_min_range_; |
| 83 | + float sqr_max_range_; |
| 84 | + |
| 85 | + vector<int> num_sectors_per_ring_; |
| 86 | + // sqr: For reducing computational complexity |
| 87 | + vector<float> sqr_boundary_ranges_; |
| 88 | + // For visualization |
| 89 | + vector<float> boundary_ranges_; |
| 90 | + vector<float> boundary_ratios_; |
| 91 | + |
| 92 | + ~ConcentricZoneModel() {} |
| 93 | + |
| 94 | + inline void set_concentric_zone_model() { |
| 95 | + set_num_sectors_for_each_ring(); |
| 96 | + // Seting ring boundaries to consider # of laser rings |
| 97 | + float smallest_incidence_angle = 90.0 + sensor_config_.lower_fov_boundary_; |
| 98 | + // For defensive programming |
| 99 | + if (tan(DEG2RAD(smallest_incidence_angle)) * sensor_height_ < min_range_) { |
| 100 | + cout << tan(DEG2RAD(smallest_incidence_angle)) * sensor_height_ << " vs " << min_range_ << endl; |
| 101 | + throw invalid_argument("[NZM] The parameter `min_r` is wrong. Check your sensor height or min. range"); |
| 102 | + } |
| 103 | + sanity_check(); |
| 104 | + set_sqr_boundary_ranges(sensor_height_, smallest_incidence_angle); |
| 105 | + } |
| 106 | + |
| 107 | + inline void sanity_check() { |
| 108 | + string SET_SAME_SIZES_OF_PARAMETERS = "Some parameters are wrong! the size of parameters should be same"; |
| 109 | + |
| 110 | + int n_z = num_zones_; |
| 111 | + int n_r = sensor_config_.num_rings_for_each_zone_.size(); |
| 112 | + int n_s = sensor_config_.num_sectors_for_each_zone_.size(); |
| 113 | + |
| 114 | + if ((n_z != n_r) || (n_z != n_s) || (n_r != n_s)) { |
| 115 | + throw invalid_argument(SET_SAME_SIZES_OF_PARAMETERS); |
| 116 | + } |
| 117 | + } |
| 118 | + |
| 119 | + bool is_boundary_set() { |
| 120 | + return is_range_boundary_set_; |
| 121 | + } |
| 122 | + inline void set_num_sectors_for_each_ring() { |
| 123 | + num_sectors_per_ring_.clear(); |
| 124 | + int count = 0; |
| 125 | + for (const auto &num_rings : sensor_config_.num_rings_for_each_zone_) { |
| 126 | + for (int j = 0; j < num_rings; ++j) { |
| 127 | + num_sectors_per_ring_.push_back(sensor_config_.num_sectors_for_each_zone_[count]); |
| 128 | + } |
| 129 | + count++; |
| 130 | + } |
| 131 | + num_total_rings_ = num_sectors_per_ring_.size(); |
| 132 | + } |
| 133 | + |
| 134 | + void set_sqr_boundary_ranges(const double sensor_height, const float smallest_incidence_angle) { |
| 135 | + /*** |
| 136 | + * Why squared value? |
| 137 | + * Because `sqrt` operation requires more computational cost |
| 138 | + */ |
| 139 | + // sqr (square): For speed-up |
| 140 | + // original : For viz polygon |
| 141 | + is_range_boundary_set_ = true; |
| 142 | + |
| 143 | + boundary_ranges_.clear(); |
| 144 | + boundary_ranges_.push_back(min_range_); |
| 145 | + sqr_boundary_ranges_.clear(); |
| 146 | + sqr_boundary_ranges_.push_back(pow(min_range_, 2)); |
| 147 | + float incidence_angle = smallest_incidence_angle; |
| 148 | + std::cout << "min_range: " << min_range_ << std::endl; |
| 149 | + |
| 150 | + float incidence_angle_prev = incidence_angle; |
| 151 | + int count = 0; |
| 152 | + for (int i = 0; i < sensor_config_.num_laser_channels_per_zone_.size(); ++i) { |
| 153 | + vector<int> num_channels_per_ring = sensor_config_.num_laser_channels_per_zone_[i]; |
| 154 | + for (int j = 0; j < num_channels_per_ring.size(); ++j) { |
| 155 | + incidence_angle += |
| 156 | + static_cast<float>(num_channels_per_ring[j]) * sensor_config_.vertical_angular_resolution_; |
| 157 | + float incidence_angle_w_margin = |
| 158 | + incidence_angle + 0.5 * sensor_config_.vertical_angular_resolution_; // For safety margin |
| 159 | + cout << "\033[1;32m" << incidence_angle_w_margin << "\033[0m" << endl; |
| 160 | + |
| 161 | + // Check whether the angle is over the 90 degrees |
| 162 | + float boundary_range; |
| 163 | + if (incidence_angle_w_margin >= 90) { |
| 164 | + cout << "\033[1;33mIncidence angle is over the 90 deg!!\033[0m" << endl; |
| 165 | + cout << "\033[1;33mBins are evenly divided!\033[0m" << endl; |
| 166 | + static float denominator = static_cast<float>(num_total_rings_ - count + 1); |
| 167 | + static float left_b = boundary_ranges_.back(); |
| 168 | + static float right_b = max_range_; |
| 169 | + float k = num_total_rings_ - count; |
| 170 | + boundary_range = left_b * (denominator - k) / denominator + max_range_ * k / denominator; |
| 171 | + } else { |
| 172 | + boundary_range = tan(DEG2RAD(incidence_angle_w_margin)) * sensor_height; |
| 173 | + incidence_angle_prev = incidence_angle_w_margin; |
| 174 | + } |
| 175 | + boundary_ranges_.push_back(boundary_range); |
| 176 | + sqr_boundary_ranges_.push_back(pow(boundary_range, 2)); |
| 177 | + cout << boundary_range << " m " << endl; |
| 178 | + ++count; |
| 179 | + } |
| 180 | + } |
| 181 | + float total_diff = boundary_ranges_.back() - min_range_; |
| 182 | + for (const auto boundary_range : boundary_ranges_) { |
| 183 | + float ratio = (boundary_range - min_range_) / total_diff; |
| 184 | + boundary_ratios_.push_back(ratio); |
| 185 | + } |
| 186 | + } |
| 187 | + |
| 188 | + inline void cout_params() { |
| 189 | + const auto &num_sectors_each_zone_ = sensor_config_.num_sectors_for_each_zone_; |
| 190 | + const auto &num_rings_each_zone_ = sensor_config_.num_rings_for_each_zone_; |
| 191 | + |
| 192 | + std::cout |
| 193 | + << (boost::format("Num. sectors: %d, %d, %d, %d") % num_sectors_each_zone_[0] % num_sectors_each_zone_[1] % |
| 194 | + num_sectors_each_zone_[2] % |
| 195 | + num_sectors_each_zone_[3]).str() << endl; |
| 196 | + std::cout << (boost::format("Num. rings: %01d, %01d, %01d, %01d") % num_rings_each_zone_[0] % |
| 197 | + num_rings_each_zone_[1] % |
| 198 | + num_rings_each_zone_[2] % |
| 199 | + num_rings_each_zone_[3]).str() << endl; |
| 200 | + } |
| 201 | + |
| 202 | + inline float xy2sqr_r(const float &x, const float &y) { |
| 203 | + return x * x + y * y; |
| 204 | + } |
| 205 | + |
| 206 | + inline float xy2theta(const float &x, const float &y) { // 0 ~ 2 * PI |
| 207 | + /* |
| 208 | + if (y >= 0) { |
| 209 | + return atan2(y, x); // 1, 2 quadrant |
| 210 | + } else { |
| 211 | + return 2 * M_PI + atan2(y, x);// 3, 4 quadrant |
| 212 | + } |
| 213 | + */ |
| 214 | + auto atan_value = atan2(y, x); // EDITED! |
| 215 | + return atan_value > 0 ? atan_value : atan_value + 2 * M_PI; // EDITED! |
| 216 | + } |
| 217 | + |
| 218 | + inline int get_ring_idx(const float &x, const float &y) { |
| 219 | + static auto &b = sqr_boundary_ranges_; |
| 220 | + float sqr_r = xy2sqr_r(x, y); |
| 221 | + // Exception for UAVs such as NTU VIRAL dataset |
| 222 | + if (sqr_r < b[0]) { |
| 223 | +// std::cout << "\033[1;33mInvalid ring idx has come:"; |
| 224 | +// std::cout << "(" << sqrt(sqr_r) << " < " << sqrt(b[0]) << ")\033[0m" << std::endl; |
| 225 | + return INVALID_RING_IDX; |
| 226 | + } |
| 227 | + if (sqr_r > sqr_max_range_) { |
| 228 | + return OVERFLOWED_IDX; |
| 229 | + } |
| 230 | + |
| 231 | + int bound_idx = lower_bound(b.begin(), b.end(), sqr_r) - b.begin(); |
| 232 | + // bound_idx: idx whose value is larger than sqr_r |
| 233 | + // Thus, b[bound_idx - 1] < sqr_r < b[bound_idx] |
| 234 | + // And note that num_rings + 1 = b.size(); thus, minus 1 is needed |
| 235 | + return bound_idx - 1; |
| 236 | + } |
| 237 | + |
| 238 | + inline int get_sector_idx(const float &x, const float &y, const int ring_idx) { |
| 239 | + float theta = xy2theta(x, y); |
| 240 | + int num_sectors = num_sectors_per_ring_[ring_idx]; |
| 241 | + float sector_size = 2.0 * M_PI / static_cast<float>(num_sectors); |
| 242 | + |
| 243 | + // min: for defensive programming |
| 244 | + return min(static_cast<int>(theta / sector_size), num_sectors - 1); |
| 245 | + } |
| 246 | + |
| 247 | + inline std::pair<int, int> get_ring_sector_idx(const float &x, const float &y) { |
| 248 | + int ring_idx = get_ring_idx(x, y); |
| 249 | + if (ring_idx == INVALID_RING_IDX) { |
| 250 | + return std::make_pair(INVALID_RING_IDX, INVALID_RING_IDX); |
| 251 | + } |
| 252 | + if (ring_idx == OVERFLOWED_IDX) { |
| 253 | + return std::make_pair(OVERFLOWED_IDX, OVERFLOWED_IDX); |
| 254 | + } |
| 255 | + |
| 256 | + int sector_idx = get_sector_idx(x, y, ring_idx); |
| 257 | + return std::make_pair(ring_idx, sector_idx); |
| 258 | + } |
| 259 | + |
| 260 | +}; |
| 261 | + |
| 262 | +#endif //PATCHWORK_SENSOR_CONFIG_HPP |
0 commit comments