feature_generator.cpp 4.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141
  1. #include "feature_generator.h"
  2. bool FeatureGenerator::init(caffe::Blob<float>* out_blob, bool use_constant_feature,double range,int width,int height)
  3. {
  4. out_blob_ = out_blob;
  5. // raw feature parameters
  6. range_ = range;
  7. width_ = width;
  8. height_ = height;
  9. min_height_ = -5.0;
  10. max_height_ = 5.0;
  11. CHECK_EQ(width_, height_)
  12. << "Current implementation version requires input_width == input_height.";
  13. // set output blob and log lookup table
  14. if(use_constant_feature){
  15. out_blob_->Reshape(1, 8, height_, width_);
  16. }else{
  17. out_blob_->Reshape(1, 6, height_, width_);
  18. }
  19. log_table_.resize(256);
  20. for (size_t i = 0; i < log_table_.size(); ++i) {
  21. log_table_[i] = std::log1p(static_cast<float>(i));
  22. }
  23. float* out_blob_data = nullptr;
  24. out_blob_data = out_blob_->mutable_cpu_data();
  25. // the pretrained model inside apollo project don't use the constant feature like direction_data_ and distance_data_
  26. int channel_index = 0;
  27. max_height_data_ = out_blob_data + out_blob_->offset(0, channel_index++);
  28. mean_height_data_ = out_blob_data + out_blob_->offset(0, channel_index++);
  29. count_data_ = out_blob_data + out_blob_->offset(0, channel_index++);
  30. if(use_constant_feature){
  31. direction_data_ = out_blob_data + out_blob_->offset(0, channel_index++);
  32. }
  33. top_intensity_data_ = out_blob_data + out_blob_->offset(0, channel_index++);
  34. mean_intensity_data_ = out_blob_data + out_blob_->offset(0, channel_index++);
  35. if(use_constant_feature){
  36. distance_data_ = out_blob_data + out_blob_->offset(0, channel_index++);
  37. }
  38. nonempty_data_ = out_blob_data + out_blob_->offset(0, channel_index++);
  39. CHECK_EQ(out_blob_->offset(0, channel_index), out_blob_->count());
  40. if(use_constant_feature){
  41. // compute direction and distance features
  42. int siz = height_ * width_;
  43. std::vector<float> direction_data(siz);
  44. std::vector<float> distance_data(siz);
  45. for (int row = 0; row < height_; ++row) {
  46. for (int col = 0; col < width_; ++col) {
  47. int idx = row * width_ + col;
  48. // * row <-> x, column <-> y
  49. float center_x = Pixel2Pc(row, height_, range_);
  50. float center_y = Pixel2Pc(col, width_, range_);
  51. constexpr double K_CV_PI = 3.1415926535897932384626433832795;
  52. direction_data[idx] =
  53. static_cast<float>(std::atan2(center_y, center_x) / (2.0 * K_CV_PI));
  54. distance_data[idx] =
  55. static_cast<float>(std::hypot(center_x, center_y) / 60.0 - 0.5);
  56. }
  57. }
  58. caffe::caffe_copy(siz, direction_data.data(), direction_data_);
  59. caffe::caffe_copy(siz, distance_data.data(), distance_data_);
  60. }
  61. return true;
  62. }
  63. float FeatureGenerator::logCount(int count)
  64. {
  65. if (count < static_cast<int>(log_table_.size())) {
  66. return log_table_[count];
  67. }
  68. return std::log(static_cast<float>(1 + count));
  69. }
  70. void FeatureGenerator::generate(
  71. const pcl::PointCloud<pcl::PointXYZI>::Ptr& pc_ptr) {
  72. const auto& points = pc_ptr->points;
  73. // DO NOT remove this line!!!
  74. // Otherwise, the gpu_data will not be updated for the later frames.
  75. // It marks the head at cpu for blob.
  76. out_blob_->mutable_cpu_data();
  77. int siz = height_ * width_;
  78. caffe::caffe_set(siz, float(-5), max_height_data_);
  79. caffe::caffe_set(siz, float(0), mean_height_data_);
  80. caffe::caffe_set(siz, float(0), count_data_);
  81. caffe::caffe_set(siz, float(0), top_intensity_data_);
  82. caffe::caffe_set(siz, float(0), mean_intensity_data_);
  83. caffe::caffe_set(siz, float(0), nonempty_data_);
  84. map_idx_.resize(points.size());
  85. float inv_res_x =
  86. 0.5 * static_cast<float>(width_) / static_cast<float>(range_);
  87. float inv_res_y =
  88. 0.5 * static_cast<float>(height_) / static_cast<float>(range_);
  89. for (size_t i = 0; i < points.size(); ++i) {
  90. if (points[i].z <= min_height_ || points[i].z >= max_height_) {
  91. map_idx_[i] = -1;
  92. continue;
  93. }
  94. // * the coordinates of x and y are exchanged here
  95. // (row <-> x, column <-> y)
  96. int pos_x = F2I(points[i].y, range_, inv_res_x); // col
  97. int pos_y = F2I(points[i].x, range_, inv_res_y); // row
  98. if (pos_x >= width_ || pos_x < 0 || pos_y >= height_ || pos_y < 0) {
  99. map_idx_[i] = -1;
  100. continue;
  101. }
  102. map_idx_[i] = pos_y * width_ + pos_x;
  103. int idx = map_idx_[i];
  104. float pz = points[i].z;
  105. // kitti dataset of intensify already in (0~1)!!!!!
  106. float pi = points[i].intensity / 255.0;
  107. // float pi = points[i].intensity;
  108. if (max_height_data_[idx] < pz) {
  109. max_height_data_[idx] = pz;
  110. top_intensity_data_[idx] = pi;
  111. }
  112. mean_height_data_[idx] += static_cast<float>(pz);
  113. mean_intensity_data_[idx] += static_cast<float>(pi);
  114. count_data_[idx] += float(1);
  115. }
  116. for (int i = 0; i < siz; ++i) {
  117. constexpr double EPS = 1e-6;
  118. if (count_data_[i] < EPS) {
  119. max_height_data_[i] = float(0);
  120. } else {
  121. mean_height_data_[i] /= count_data_[i];
  122. mean_intensity_data_[i] /= count_data_[i];
  123. nonempty_data_[i] = float(1);
  124. }
  125. count_data_[i] = logCount(static_cast<int>(count_data_[i]));
  126. }
  127. }