|
| 1 | +// Copyright 2021 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 | + |
| 15 | +#ifndef LIDAR_CENTERPOINT__CENTERPOINT_CONFIG_HPP_ |
| 16 | +#define LIDAR_CENTERPOINT__CENTERPOINT_CONFIG_HPP_ |
| 17 | + |
| 18 | +#include <cstddef> |
| 19 | +#include <vector> |
| 20 | + |
| 21 | +namespace centerpoint |
| 22 | +{ |
| 23 | +class CenterPointConfig |
| 24 | +{ |
| 25 | +public: |
| 26 | + explicit CenterPointConfig( |
| 27 | + const std::size_t class_size, const float point_feature_size, const std::size_t max_voxel_size, |
| 28 | + const std::vector<double> & point_cloud_range, const std::vector<double> & voxel_size, |
| 29 | + const std::size_t downsample_factor, const std::size_t encoder_in_feature_size, |
| 30 | + const float score_threshold, const float circle_nms_dist_threshold) |
| 31 | + { |
| 32 | + class_size_ = class_size; |
| 33 | + point_feature_size_ = point_feature_size; |
| 34 | + max_voxel_size_ = max_voxel_size; |
| 35 | + if (point_cloud_range.size() == 6) { |
| 36 | + range_min_x_ = static_cast<float>(point_cloud_range[0]); |
| 37 | + range_min_y_ = static_cast<float>(point_cloud_range[1]); |
| 38 | + range_min_z_ = static_cast<float>(point_cloud_range[2]); |
| 39 | + range_max_x_ = static_cast<float>(point_cloud_range[3]); |
| 40 | + range_max_y_ = static_cast<float>(point_cloud_range[4]); |
| 41 | + range_max_z_ = static_cast<float>(point_cloud_range[5]); |
| 42 | + } |
| 43 | + if (voxel_size.size() == 3) { |
| 44 | + voxel_size_x_ = static_cast<float>(voxel_size[0]); |
| 45 | + voxel_size_y_ = static_cast<float>(voxel_size[1]); |
| 46 | + voxel_size_z_ = static_cast<float>(voxel_size[2]); |
| 47 | + } |
| 48 | + downsample_factor_ = downsample_factor; |
| 49 | + encoder_in_feature_size_ = encoder_in_feature_size; |
| 50 | + |
| 51 | + if (score_threshold > 0 && score_threshold < 1) { |
| 52 | + score_threshold_ = score_threshold; |
| 53 | + } |
| 54 | + |
| 55 | + if (circle_nms_dist_threshold > 0) { |
| 56 | + circle_nms_dist_threshold_ = circle_nms_dist_threshold; |
| 57 | + } |
| 58 | + |
| 59 | + grid_size_x_ = static_cast<std::size_t>((range_max_x_ - range_min_x_) / voxel_size_x_); |
| 60 | + grid_size_y_ = static_cast<std::size_t>((range_max_y_ - range_min_y_) / voxel_size_y_); |
| 61 | + grid_size_z_ = static_cast<std::size_t>((range_max_z_ - range_min_z_) / voxel_size_z_); |
| 62 | + offset_x_ = range_min_x_ + voxel_size_x_ / 2; |
| 63 | + offset_y_ = range_min_y_ + voxel_size_y_ / 2; |
| 64 | + offset_z_ = range_min_z_ + voxel_size_z_ / 2; |
| 65 | + down_grid_size_x_ = grid_size_x_ / downsample_factor_; |
| 66 | + down_grid_size_y_ = grid_size_y_ / downsample_factor_; |
| 67 | + }; |
| 68 | + |
| 69 | + // input params |
| 70 | + std::size_t class_size_{3}; |
| 71 | + const std::size_t point_dim_size_{3}; // x, y and z |
| 72 | + std::size_t point_feature_size_{4}; // x, y, z and timelag |
| 73 | + std::size_t max_point_in_voxel_size_{32}; |
| 74 | + std::size_t max_voxel_size_{40000}; |
| 75 | + float range_min_x_{-89.6f}; |
| 76 | + float range_min_y_{-89.6f}; |
| 77 | + float range_min_z_{-3.0f}; |
| 78 | + float range_max_x_{89.6f}; |
| 79 | + float range_max_y_{89.6f}; |
| 80 | + float range_max_z_{5.0f}; |
| 81 | + float voxel_size_x_{0.32f}; |
| 82 | + float voxel_size_y_{0.32f}; |
| 83 | + float voxel_size_z_{8.0f}; |
| 84 | + |
| 85 | + // network params |
| 86 | + const std::size_t batch_size_{1}; |
| 87 | + std::size_t downsample_factor_{2}; |
| 88 | + std::size_t encoder_in_feature_size_{9}; |
| 89 | + const std::size_t encoder_out_feature_size_{32}; |
| 90 | + const std::size_t head_out_size_{6}; |
| 91 | + const std::size_t head_out_offset_size_{2}; |
| 92 | + const std::size_t head_out_z_size_{1}; |
| 93 | + const std::size_t head_out_dim_size_{3}; |
| 94 | + const std::size_t head_out_rot_size_{2}; |
| 95 | + const std::size_t head_out_vel_size_{2}; |
| 96 | + |
| 97 | + // post-process params |
| 98 | + float score_threshold_{0.4f}; |
| 99 | + float circle_nms_dist_threshold_{1.5f}; |
| 100 | + |
| 101 | + // calculated params |
| 102 | + std::size_t grid_size_x_ = (range_max_x_ - range_min_x_) / voxel_size_x_; |
| 103 | + std::size_t grid_size_y_ = (range_max_y_ - range_min_y_) / voxel_size_y_; |
| 104 | + std::size_t grid_size_z_ = (range_max_z_ - range_min_z_) / voxel_size_z_; |
| 105 | + float offset_x_ = range_min_x_ + voxel_size_x_ / 2; |
| 106 | + float offset_y_ = range_min_y_ + voxel_size_y_ / 2; |
| 107 | + float offset_z_ = range_min_z_ + voxel_size_z_ / 2; |
| 108 | + std::size_t down_grid_size_x_ = grid_size_x_ / downsample_factor_; |
| 109 | + std::size_t down_grid_size_y_ = grid_size_y_ / downsample_factor_; |
| 110 | +}; |
| 111 | + |
| 112 | +} // namespace centerpoint |
| 113 | + |
| 114 | +#endif // LIDAR_CENTERPOINT__CENTERPOINT_CONFIG_HPP_ |
0 commit comments