提交 f6374fa1 编写于 作者: J Jun Zhu 提交者: weidezhang

[perception] remove OpenCV dependency in CNNSegmentation (#1428)

* [perception] remove OpenCV dependency in CNNSegmentation

* [perception] modify linkstatic back to dynamic link

* [perception] delete commanded lines in CNNSegmentation
上级 e3f82ba2
...@@ -25,7 +25,6 @@ cc_library( ...@@ -25,7 +25,6 @@ cc_library(
cc_library( cc_library(
name = "cnnseg_util", name = "cnnseg_util",
hdrs = ["util.h"], hdrs = ["util.h"],
deps = ["@opencv2//:core"],
) )
cc_library( cc_library(
......
...@@ -128,7 +128,7 @@ bool CNNSegmentation::Segment(const pcl_util::PointCloudPtr& pc_ptr, ...@@ -128,7 +128,7 @@ bool CNNSegmentation::Segment(const pcl_util::PointCloudPtr& pc_ptr,
use_full_cloud_ = use_full_cloud_ =
cnnseg_param_.use_full_cloud() && (options.origin_cloud != nullptr); cnnseg_param_.use_full_cloud() && (options.origin_cloud != nullptr);
timer_.Tic(); PERF_BLOCK_START();
// generate raw features // generate raw features
if (use_full_cloud_) { if (use_full_cloud_) {
...@@ -136,34 +136,26 @@ bool CNNSegmentation::Segment(const pcl_util::PointCloudPtr& pc_ptr, ...@@ -136,34 +136,26 @@ bool CNNSegmentation::Segment(const pcl_util::PointCloudPtr& pc_ptr,
} else { } else {
feature_generator_->Generate(pc_ptr); feature_generator_->Generate(pc_ptr);
} }
feat_time_ = timer_.Toc(true); PERF_BLOCK_END("[CNNSeg] feature generation");
// network forward process // network forward process
#ifndef CPU_ONLY #ifndef CPU_ONLY
caffe::Caffe::set_mode(caffe::Caffe::GPU); caffe::Caffe::set_mode(caffe::Caffe::GPU);
#endif #endif
caffe_net_->Forward(); caffe_net_->Forward();
network_time_ = timer_.Toc(true); PERF_BLOCK_END("[CNNSeg] CNN forward");
// clutser points and construct segments/objects // clutser points and construct segments/objects
cluster2d_->Cluster(*category_pt_blob_, *instance_pt_blob_, pc_ptr, cluster2d_->Cluster(*category_pt_blob_, *instance_pt_blob_, pc_ptr,
valid_indices, cnnseg_param_.objectness_thresh(), valid_indices, cnnseg_param_.objectness_thresh(),
cnnseg_param_.use_all_grids_for_clustering()); cnnseg_param_.use_all_grids_for_clustering());
clust_time_ = timer_.Toc(true); PERF_BLOCK_END("[CNNSeg] clustering");
cluster2d_->Filter(*confidence_pt_blob_, *height_pt_blob_); cluster2d_->Filter(*confidence_pt_blob_, *height_pt_blob_);
cluster2d_->GetObjects(cnnseg_param_.confidence_thresh(), cluster2d_->GetObjects(cnnseg_param_.confidence_thresh(),
cnnseg_param_.height_thresh(), cnnseg_param_.height_thresh(),
cnnseg_param_.min_pts_num(), objects); cnnseg_param_.min_pts_num(), objects);
post_time_ = timer_.Toc(true); PERF_BLOCK_END("[CNNSeg] post-processing");
tot_time_ = feat_time_ + network_time_ + clust_time_ + post_time_;
AINFO << "Total runtime: " << tot_time_ << "ms\t"
<< " Feature generation: " << feat_time_ << "ms\t"
<< " CNN forward: " << network_time_ << "ms\t"
<< " Clustering: " << clust_time_ << "ms\t"
<< " Post-processing: " << post_time_ << "ms";
return true; return true;
} }
......
...@@ -24,10 +24,10 @@ ...@@ -24,10 +24,10 @@
#include "caffe/caffe.hpp" #include "caffe/caffe.hpp"
#include "modules/common/log.h" #include "modules/common/log.h"
#include "modules/perception/lib/pcl_util/pcl_types.h" #include "modules/perception/lib/pcl_util/pcl_types.h"
#include "modules/perception/lib/base/timer.h"
#include "modules/perception/obstacle/base/object.h" #include "modules/perception/obstacle/base/object.h"
#include "modules/perception/obstacle/lidar/interface/base_segmentation.h" #include "modules/perception/obstacle/lidar/interface/base_segmentation.h"
#include "modules/perception/obstacle/lidar/segmentation/cnnseg/proto/cnnseg.pb.h" #include "modules/perception/obstacle/lidar/segmentation/cnnseg/proto/cnnseg.pb.h"
#include "modules/perception/obstacle/lidar/segmentation/cnnseg/util.h"
#include "modules/perception/obstacle/lidar/segmentation/cnnseg/feature_generator.h" #include "modules/perception/obstacle/lidar/segmentation/cnnseg/feature_generator.h"
#include "modules/perception/obstacle/lidar/segmentation/cnnseg/cluster2d.h" #include "modules/perception/obstacle/lidar/segmentation/cnnseg/cluster2d.h"
...@@ -89,12 +89,7 @@ class CNNSegmentation : public BaseSegmentation { ...@@ -89,12 +89,7 @@ class CNNSegmentation : public BaseSegmentation {
std::shared_ptr<cnnseg::Cluster2D> cluster2d_; std::shared_ptr<cnnseg::Cluster2D> cluster2d_;
// timer // timer
cnnseg::Timer timer_; Timer timer_;
double feat_time_ = 0.0;
double network_time_ = 0.0;
double clust_time_ = 0.0;
double post_time_ = 0.0;
double tot_time_ = 0.0;
DISALLOW_COPY_AND_ASSIGN(CNNSegmentation); DISALLOW_COPY_AND_ASSIGN(CNNSegmentation);
}; };
......
...@@ -23,6 +23,7 @@ ...@@ -23,6 +23,7 @@
#include <unordered_set> #include <unordered_set>
#include <vector> #include <vector>
#include "opencv2/opencv.hpp"
#include "gtest/gtest.h" #include "gtest/gtest.h"
#include "modules/common/log.h" #include "modules/common/log.h"
#include "modules/perception/common/perception_gflags.h" #include "modules/perception/common/perception_gflags.h"
......
...@@ -18,34 +18,11 @@ ...@@ -18,34 +18,11 @@
#define MODULES_PERCEPTION_OBSTACLE_LIDAR_SEGMENTATION_CNNSEG_UTIL_H_ #define MODULES_PERCEPTION_OBSTACLE_LIDAR_SEGMENTATION_CNNSEG_UTIL_H_
#include <string> #include <string>
#include "opencv2/opencv.hpp"
namespace apollo { namespace apollo {
namespace perception { namespace perception {
namespace cnnseg { namespace cnnseg {
class Timer {
public:
Timer() {
Tic();
scale_ = 1.0 / (static_cast<double>(cvGetTickFrequency()) * 1000.);
}
void Tic() {
start_ = static_cast<double>(cv::getTickCount());
}
double Toc(bool reset = false) {
double time = (static_cast<double>(cvGetTickCount()) - start_) * scale_;
if (reset) {
Tic();
}
return time;
}
private:
double start_;
double scale_;
};
inline int F2I(float val, float ori, float scale) { inline int F2I(float val, float ori, float scale) {
return static_cast<int>(std::floor((ori - val) * scale)); return static_cast<int>(std::floor((ori - val) * scale));
} }
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册