point_pillars_detection.cc 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381
  1. /******************************************************************************
  2. * Copyright 2020 The Apollo Authors. All Rights Reserved.
  3. *
  4. * Licensed under the Apache License, Version 2.0 (the "License");
  5. * you may not use this file except in compliance with the License.
  6. * You may obtain a copy of the License at
  7. *
  8. * http://www.apache.org/licenses/LICENSE-2.0
  9. *
  10. * Unless required by applicable law or agreed to in writing, software
  11. * distributed under the License is distributed on an "AS IS" BASIS,
  12. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  13. * See the License for the specific language governing permissions and
  14. * limitations under the License.
  15. *****************************************************************************/
  16. #include "modules/perception/lidar/lib/detection/lidar_point_pillars/point_pillars_detection.h"
  17. #include <algorithm>
  18. #include <numeric>
  19. #include <random>
  20. #include <cuda_runtime_api.h>
  21. #include "cyber/common/log.h"
  22. #include "modules/perception/base/object_pool_types.h"
  23. #include "modules/perception/base/point_cloud_util.h"
  24. #include "modules/perception/common/perception_gflags.h"
  25. #include "modules/perception/lidar/common/lidar_timer.h"
  26. #include "modules/perception/lidar/common/pcl_util.h"
  27. #include "modules/perception/lidar/lib/detection/lidar_point_pillars/params.h"
  28. namespace apollo {
  29. namespace perception {
  30. namespace lidar {
  31. using base::Object;
  32. using base::PointD;
  33. using base::PointF;
  34. PointPillarsDetection::PointPillarsDetection()
  35. : x_min_(Params::kMinXRange),
  36. x_max_(Params::kMaxXRange),
  37. y_min_(Params::kMinYRange),
  38. y_max_(Params::kMaxYRange),
  39. z_min_(Params::kMinZRange),
  40. z_max_(Params::kMaxZRange) {
  41. if (FLAGS_enable_ground_removal) {
  42. z_min_ = std::max(z_min_, static_cast<float>(FLAGS_ground_removal_height));
  43. }
  44. }
  45. // TODO(chenjiahao):
  46. // specify score threshold and nms over lap threshold for each class.
  47. bool PointPillarsDetection::Init(const DetectionInitOptions& options) {
  48. point_pillars_ptr_.reset(new PointPillars(
  49. FLAGS_reproduce_result_mode, FLAGS_score_threshold,
  50. FLAGS_nms_overlap_threshold, FLAGS_pfe_torch_file, FLAGS_rpn_onnx_file));
  51. return true;
  52. }
  53. bool PointPillarsDetection::Detect(const DetectionOptions& options,
  54. LidarFrame* frame) {
  55. // check input
  56. if (frame == nullptr) {
  57. AERROR << "Input null frame ptr.";
  58. return false;
  59. }
  60. if (frame->cloud == nullptr) {
  61. AERROR << "Input null frame cloud.";
  62. return false;
  63. }
  64. if (frame->cloud->size() == 0) {
  65. AERROR << "Input none points.";
  66. return false;
  67. }
  68. // record input cloud and lidar frame
  69. original_cloud_ = frame->cloud;
  70. original_world_cloud_ = frame->world_cloud;
  71. lidar_frame_ref_ = frame;
  72. // check output
  73. frame->segmented_objects.clear();
  74. if (cudaSetDevice(FLAGS_gpu_id) != cudaSuccess) {
  75. AERROR << "Failed to set device to gpu " << FLAGS_gpu_id;
  76. return false;
  77. }
  78. Timer timer;
  79. int num_points;
  80. cur_cloud_ptr_ = std::shared_ptr<base::PointFCloud>(
  81. new base::PointFCloud(*original_cloud_));
  82. // down sample the point cloud through filtering beams
  83. if (FLAGS_enable_downsample_beams) {
  84. base::PointFCloudPtr downsample_beams_cloud_ptr(new base::PointFCloud());
  85. if (DownSamplePointCloudBeams(original_cloud_, downsample_beams_cloud_ptr,
  86. FLAGS_downsample_beams_factor)) {
  87. cur_cloud_ptr_ = downsample_beams_cloud_ptr;
  88. } else {
  89. AWARN << "Down-sample beams factor must be >= 1. Cancel down-sampling."
  90. " Current factor: "
  91. << FLAGS_downsample_beams_factor;
  92. }
  93. }
  94. // down sample the point cloud through filtering voxel grid
  95. if (FLAGS_enable_downsample_pointcloud) {
  96. pcl::PointCloud<pcl::PointXYZI>::Ptr pcl_cloud_ptr(
  97. new pcl::PointCloud<pcl::PointXYZI>());
  98. pcl::PointCloud<pcl::PointXYZI>::Ptr filtered_cloud_ptr(
  99. new pcl::PointCloud<pcl::PointXYZI>());
  100. TransformToPCLXYZI(*cur_cloud_ptr_, pcl_cloud_ptr);
  101. DownSampleCloudByVoxelGrid(pcl_cloud_ptr, filtered_cloud_ptr,
  102. FLAGS_downsample_voxel_size_x,
  103. FLAGS_downsample_voxel_size_y,
  104. FLAGS_downsample_voxel_size_z);
  105. // transform pcl point cloud to apollo point cloud
  106. base::PointFCloudPtr downsample_voxel_cloud_ptr(new base::PointFCloud());
  107. TransformFromPCLXYZI(filtered_cloud_ptr, downsample_voxel_cloud_ptr);
  108. cur_cloud_ptr_ = downsample_voxel_cloud_ptr;
  109. }
  110. downsample_time_ = timer.toc(true);
  111. num_points = cur_cloud_ptr_->size();
  112. AINFO << "num points before fusing: " << num_points;
  113. // fuse clouds of preceding frames with current cloud
  114. cur_cloud_ptr_->mutable_points_timestamp()->assign(cur_cloud_ptr_->size(),
  115. 0.0);
  116. if (FLAGS_enable_fuse_frames && FLAGS_num_fuse_frames > 1) {
  117. // before fusing
  118. while (!prev_world_clouds_.empty() &&
  119. frame->timestamp - prev_world_clouds_.front()->get_timestamp() >
  120. FLAGS_fuse_time_interval) {
  121. prev_world_clouds_.pop_front();
  122. }
  123. // transform current cloud to world coordinate and save to a new ptr
  124. base::PointDCloudPtr cur_world_cloud_ptr =
  125. std::make_shared<base::PointDCloud>();
  126. for (size_t i = 0; i < cur_cloud_ptr_->size(); ++i) {
  127. auto& pt = cur_cloud_ptr_->at(i);
  128. Eigen::Vector3d trans_point(pt.x, pt.y, pt.z);
  129. trans_point = lidar_frame_ref_->lidar2world_pose * trans_point;
  130. PointD world_point;
  131. world_point.x = trans_point(0);
  132. world_point.y = trans_point(1);
  133. world_point.z = trans_point(2);
  134. world_point.intensity = pt.intensity;
  135. cur_world_cloud_ptr->push_back(world_point);
  136. }
  137. cur_world_cloud_ptr->set_timestamp(frame->timestamp);
  138. // fusing clouds
  139. for (auto& prev_world_cloud_ptr : prev_world_clouds_) {
  140. num_points += prev_world_cloud_ptr->size();
  141. }
  142. FuseCloud(cur_cloud_ptr_, prev_world_clouds_);
  143. // after fusing
  144. while (static_cast<int>(prev_world_clouds_.size()) >=
  145. FLAGS_num_fuse_frames - 1) {
  146. prev_world_clouds_.pop_front();
  147. }
  148. prev_world_clouds_.emplace_back(cur_world_cloud_ptr);
  149. }
  150. AINFO << "num points after fusing: " << num_points;
  151. fuse_time_ = timer.toc(true);
  152. // shuffle points and cut off
  153. if (FLAGS_enable_shuffle_points) {
  154. num_points = std::min(num_points, FLAGS_max_num_points);
  155. std::vector<int> point_indices = GenerateIndices(0, num_points, true);
  156. base::PointFCloudPtr shuffle_cloud_ptr(
  157. new base::PointFCloud(*cur_cloud_ptr_, point_indices));
  158. cur_cloud_ptr_ = shuffle_cloud_ptr;
  159. }
  160. shuffle_time_ = timer.toc(true);
  161. // point cloud to array
  162. float* points_array = new float[num_points * FLAGS_num_point_feature]();
  163. CloudToArray(cur_cloud_ptr_, points_array, FLAGS_normalizing_factor);
  164. cloud_to_array_time_ = timer.toc(true);
  165. // inference
  166. std::vector<float> out_detections;
  167. std::vector<int> out_labels;
  168. point_pillars_ptr_->DoInference(points_array, num_points, &out_detections,
  169. &out_labels);
  170. inference_time_ = timer.toc(true);
  171. // transfer output bounding boxes to objects
  172. GetObjects(&frame->segmented_objects, frame->lidar2world_pose,
  173. &out_detections, &out_labels);
  174. collect_time_ = timer.toc(true);
  175. AINFO << "PointPillars: " << "\n"
  176. << "down sample: " << downsample_time_ << "\t"
  177. << "fuse: " << fuse_time_ << "\t"
  178. << "shuffle: " << shuffle_time_ << "\t"
  179. << "cloud_to_array: " << cloud_to_array_time_ << "\t"
  180. << "inference: " << inference_time_ << "\t"
  181. << "collect: " << collect_time_;
  182. delete[] points_array;
  183. return true;
  184. }
  185. void PointPillarsDetection::CloudToArray(const base::PointFCloudPtr& pc_ptr,
  186. float* out_points_array,
  187. const float normalizing_factor) {
  188. for (size_t i = 0; i < pc_ptr->size(); ++i) {
  189. const auto& point = pc_ptr->at(i);
  190. float x = point.x;
  191. float y = point.y;
  192. float z = point.z;
  193. float intensity = point.intensity;
  194. if (z < z_min_ || z > z_max_ || y < y_min_ || y > y_max_ || x < x_min_ ||
  195. x > x_max_) {
  196. continue;
  197. }
  198. out_points_array[i * FLAGS_num_point_feature + 0] = x;
  199. out_points_array[i * FLAGS_num_point_feature + 1] = y;
  200. out_points_array[i * FLAGS_num_point_feature + 2] = z;
  201. out_points_array[i * FLAGS_num_point_feature + 3] =
  202. intensity / normalizing_factor;
  203. // delta of timestamp between prev and cur frames
  204. out_points_array[i * FLAGS_num_point_feature + 4] =
  205. static_cast<float>(pc_ptr->points_timestamp(i));
  206. }
  207. }
  208. void PointPillarsDetection::FuseCloud(
  209. const base::PointFCloudPtr& out_cloud_ptr,
  210. const std::deque<base::PointDCloudPtr>& fuse_clouds) {
  211. for (auto iter = fuse_clouds.rbegin(); iter != fuse_clouds.rend(); ++iter) {
  212. double delta_t = lidar_frame_ref_->timestamp - (*iter)->get_timestamp();
  213. // transform prev world point cloud to current sensor's coordinates
  214. for (size_t i = 0; i < (*iter)->size(); ++i) {
  215. auto& point = (*iter)->at(i);
  216. Eigen::Vector3d trans_point(point.x, point.y, point.z);
  217. trans_point = lidar_frame_ref_->lidar2world_pose.inverse() * trans_point;
  218. base::PointF pt;
  219. pt.x = static_cast<float>(trans_point(0));
  220. pt.y = static_cast<float>(trans_point(1));
  221. pt.z = static_cast<float>(trans_point(2));
  222. pt.intensity = static_cast<float>(point.intensity);
  223. // delta of time between current and prev frame
  224. out_cloud_ptr->push_back(pt, delta_t);
  225. }
  226. }
  227. }
  228. std::vector<int> PointPillarsDetection::GenerateIndices(int start_index,
  229. int size,
  230. bool shuffle) {
  231. // create a range number array
  232. std::vector<int> indices(size);
  233. std::iota(indices.begin(), indices.end(), start_index);
  234. // shuffle the index array
  235. if (shuffle) {
  236. unsigned seed = 0;
  237. std::shuffle(indices.begin(), indices.end(),
  238. std::default_random_engine(seed));
  239. }
  240. return indices;
  241. }
  242. void PointPillarsDetection::GetObjects(
  243. std::vector<std::shared_ptr<Object>>* objects, const Eigen::Affine3d& pose,
  244. std::vector<float>* detections, std::vector<int>* labels) {
  245. int num_objects = detections->size() / FLAGS_num_output_box_feature;
  246. objects->clear();
  247. base::ObjectPool::Instance().BatchGet(num_objects, objects);
  248. for (int i = 0; i < num_objects; ++i) {
  249. auto& object = objects->at(i);
  250. object->id = i;
  251. // read params of bounding box
  252. float x = detections->at(i * FLAGS_num_output_box_feature + 0);
  253. float y = detections->at(i * FLAGS_num_output_box_feature + 1);
  254. float z = detections->at(i * FLAGS_num_output_box_feature + 2);
  255. float dx = detections->at(i * FLAGS_num_output_box_feature + 4);
  256. float dy = detections->at(i * FLAGS_num_output_box_feature + 3);
  257. float dz = detections->at(i * FLAGS_num_output_box_feature + 5);
  258. float yaw = detections->at(i * FLAGS_num_output_box_feature + 6);
  259. yaw += M_PI / 2;
  260. yaw = std::atan2(sinf(yaw), cosf(yaw));
  261. yaw = -yaw;
  262. // directions
  263. object->theta = yaw;
  264. object->direction[0] = cosf(yaw);
  265. object->direction[1] = sinf(yaw);
  266. object->direction[2] = 0;
  267. object->lidar_supplement.is_orientation_ready = true;
  268. // compute vertexes of bounding box and transform to world coordinate
  269. object->lidar_supplement.num_points_in_roi = 8;
  270. object->lidar_supplement.on_use = true;
  271. object->lidar_supplement.is_background = false;
  272. float roll = 0, pitch = 0;
  273. Eigen::Quaternionf quater =
  274. Eigen::AngleAxisf(roll, Eigen::Vector3f::UnitX()) *
  275. Eigen::AngleAxisf(pitch, Eigen::Vector3f::UnitY()) *
  276. Eigen::AngleAxisf(yaw, Eigen::Vector3f::UnitZ());
  277. Eigen::Translation3f translation(x, y, z);
  278. Eigen::Affine3f affine3f = translation * quater.toRotationMatrix();
  279. for (float vx : std::vector<float>{dx / 2, -dx / 2}) {
  280. for (float vy : std::vector<float>{dy / 2, -dy / 2}) {
  281. for (float vz : std::vector<float>{0, dz}) {
  282. Eigen::Vector3f v3f(vx, vy, vz);
  283. v3f = affine3f * v3f;
  284. PointF point;
  285. point.x = v3f.x();
  286. point.y = v3f.y();
  287. point.z = v3f.z();
  288. object->lidar_supplement.cloud.push_back(point);
  289. Eigen::Vector3d trans_point(point.x, point.y, point.z);
  290. trans_point = pose * trans_point;
  291. PointD world_point;
  292. world_point.x = trans_point(0);
  293. world_point.y = trans_point(1);
  294. world_point.z = trans_point(2);
  295. object->lidar_supplement.cloud_world.push_back(world_point);
  296. }
  297. }
  298. }
  299. // classification
  300. object->lidar_supplement.raw_probs.push_back(std::vector<float>(
  301. static_cast<int>(base::ObjectType::MAX_OBJECT_TYPE), 0.f));
  302. object->lidar_supplement.raw_classification_methods.push_back(Name());
  303. object->sub_type = GetObjectSubType(labels->at(i));
  304. object->type = base::kSubType2TypeMap.at(object->sub_type);
  305. object->lidar_supplement.raw_probs.back()[static_cast<int>(object->type)] =
  306. 1.0f;
  307. // copy to type
  308. object->type_probs.assign(object->lidar_supplement.raw_probs.back().begin(),
  309. object->lidar_supplement.raw_probs.back().end());
  310. }
  311. }
  312. // TODO(all): update the base ObjectSubType with more fine-grained types
  313. // TODO(chenjiahao): move types into an array in the same order as offline
  314. base::ObjectSubType PointPillarsDetection::GetObjectSubType(const int label) {
  315. switch (label) {
  316. case 0:
  317. return base::ObjectSubType::BUS;
  318. case 1:
  319. return base::ObjectSubType::CAR;
  320. case 2: // construction vehicle
  321. return base::ObjectSubType::UNKNOWN_MOVABLE;
  322. case 3:
  323. return base::ObjectSubType::TRUCK;
  324. case 4: // barrier
  325. return base::ObjectSubType::UNKNOWN_UNMOVABLE;
  326. case 5:
  327. return base::ObjectSubType::CYCLIST;
  328. case 6:
  329. return base::ObjectSubType::MOTORCYCLIST;
  330. case 7:
  331. return base::ObjectSubType::PEDESTRIAN;
  332. case 8:
  333. return base::ObjectSubType::TRAFFICCONE;
  334. default:
  335. return base::ObjectSubType::UNKNOWN;
  336. }
  337. }
  338. } // namespace lidar
  339. } // namespace perception
  340. } // namespace apollo