27 #include <Eigen/Dense>
29 #include <opencv2/core/core.hpp>
30 #include <opencv2/opencv.hpp>
32 #include <boost/date_time/posix_time/posix_time.hpp>
39 void print_stats(std::string
title, std::vector<double> times, std::string title2 =
"", std::vector<int> stats = {}) {
44 for (
size_t i = 0; i < times.size(); i++) {
45 assert(!std::isnan(times.at(i)));
47 rmse += times.at(i) * times.at(i);
50 rmse = std::sqrt(rmse / times.size());
54 for (
size_t i = 0; i < times.size(); i++) {
55 std += std::pow(times.at(i) - mean, 2);
57 std = std::sqrt(
std / (times.size() - 1));
64 for (
size_t i = 0; i < stats.size(); i++) {
65 assert(!std::isnan(stats.at(i)));
68 mean2 /= stats.size();
69 PRINT_INFO(
"%s: %.3f +- %.3f ms (%.2f avg %s)\n",
title.c_str(), mean,
std, mean2, title2.c_str());
74 int main(
int argc,
char **argv) {
77 std::string verbosity =
"INFO";
82 int big_matrix = 1000;
83 int big_matrix_eigen1 = 300;
84 int big_matrix_eigen2 = 900;
86 int fast_threshold = 30;
87 int max_features = 500;
88 cv::Size win_size = cv::Size(15, 15);
89 cv::TermCriteria term_crit = cv::TermCriteria(cv::TermCriteria::COUNT | cv::TermCriteria::EPS, 30, 0.01);
92 cv::Mat img1(big_matrix, big_matrix, CV_8UC1);
93 cv::Mat img3(big_matrix, big_matrix, CV_8UC3);
94 std::vector<double> times_ms;
95 std::vector<int> extra_stats;
99 for (
int i = 0; i < num_trials; i++) {
100 auto rT1 = boost::posix_time::microsec_clock::local_time();
101 cv::randu(img3, cv::Scalar(0, 0, 0), cv::Scalar(255, 255, 255));
102 auto rT2 = boost::posix_time::microsec_clock::local_time();
103 times_ms.push_back((rT2 - rT1).total_microseconds() * 1e-3);
109 for (
int i = 0; i < num_trials; i++) {
110 cv::randu(img1, cv::Scalar(0), cv::Scalar(255));
111 auto rT1 = boost::posix_time::microsec_clock::local_time();
112 cv::equalizeHist(img1, img1);
113 auto rT2 = boost::posix_time::microsec_clock::local_time();
114 times_ms.push_back((rT2 - rT1).total_microseconds() * 1e-3);
116 print_stats(
"OPENCV: HISTOGRAM EQUALIZATION", times_ms);
120 for (
int i = 0; i < num_trials; i++) {
121 cv::randu(img1, cv::Scalar(0), cv::Scalar(255));
122 auto rT1 = boost::posix_time::microsec_clock::local_time();
123 std::vector<cv::Mat> imgpyr;
124 cv::buildOpticalFlowPyramid(img1, imgpyr, win_size, pyr_levels);
125 auto rT2 = boost::posix_time::microsec_clock::local_time();
126 times_ms.push_back((rT2 - rT1).total_microseconds() * 1e-3);
128 print_stats(
"OPENCV: BUILD OPTICAL FLOW PYRAMID", times_ms);
133 for (
int i = 0; i < num_trials; i++) {
134 cv::randu(img1, cv::Scalar(0), cv::Scalar(255));
135 auto rT1 = boost::posix_time::microsec_clock::local_time();
136 std::vector<cv::KeyPoint> pts_new;
137 cv::FAST(img1, pts_new, fast_threshold,
true);
138 auto rT2 = boost::posix_time::microsec_clock::local_time();
139 times_ms.push_back((rT2 - rT1).total_microseconds() * 1e-3);
140 extra_stats.push_back((
int)pts_new.size());
142 print_stats(
"OPENCV: FAST FEATURE EXTRACTION", times_ms,
"feats", extra_stats);
147 for (
int i = 0; i < num_trials; i++) {
148 std::vector<cv::Mat> imgpyr1, imgpyr2;
149 cv::buildOpticalFlowPyramid(img1, imgpyr1, win_size, pyr_levels);
150 std::vector<cv::KeyPoint> pts0_tmp;
151 cv::FAST(img1, pts0_tmp, fast_threshold,
true);
152 std::sort(pts0_tmp.begin(), pts0_tmp.end(), [](cv::KeyPoint first, cv::KeyPoint second) { return first.response > second.response; });
153 std::vector<cv::Point2f> pts0;
154 for (
size_t j = 0; j < pts0_tmp.size() && (
int)j < max_features; j++)
155 pts0.push_back(pts0_tmp.at(j).pt);
156 cv::randu(img1, cv::Scalar(0), cv::Scalar(255));
157 cv::buildOpticalFlowPyramid(img1, imgpyr2, win_size, pyr_levels);
158 auto rT1 = boost::posix_time::microsec_clock::local_time();
159 std::vector<uchar> mask_klt;
160 std::vector<float> error;
161 std::vector<cv::Point2f> pts1, pts1_good;
162 cv::calcOpticalFlowPyrLK(imgpyr1, imgpyr2, pts0, pts1, mask_klt, error, win_size, pyr_levels, term_crit);
163 for (
size_t j = 0; j < mask_klt.size(); j++) {
165 pts1_good.push_back(pts1.at(j));
167 auto rT2 = boost::posix_time::microsec_clock::local_time();
168 times_ms.push_back((rT2 - rT1).total_microseconds() * 1e-3);
169 extra_stats.push_back((
int)pts1_good.size());
171 print_stats(
"OPENCV: KLT OPTICAL FLOW", times_ms,
"feats", extra_stats);
179 for (
int i = 0; i < num_trials; i++) {
180 auto rT1 = boost::posix_time::microsec_clock::local_time();
181 Eigen::MatrixXd mat1 = Eigen::MatrixXd::Random(big_matrix_eigen1, big_matrix_eigen1);
182 Eigen::MatrixXd mat2 = Eigen::MatrixXd::Random(big_matrix_eigen1, big_matrix_eigen1);
183 auto rT2 = boost::posix_time::microsec_clock::local_time();
184 times_ms.push_back((rT2 - rT1).total_microseconds() * 1e-3);
186 print_stats(
"EIGEN3(double): RANDOM BIG MATRIX", times_ms);
190 for (
int i = 0; i < num_trials; i++) {
191 Eigen::MatrixXd mat1 = Eigen::MatrixXd::Random(big_matrix_eigen1, big_matrix_eigen1);
192 Eigen::MatrixXd mat2 = Eigen::MatrixXd::Random(big_matrix_eigen1, big_matrix_eigen1);
193 auto rT1 = boost::posix_time::microsec_clock::local_time();
194 Eigen::MatrixXd mat3 = mat1 * mat2;
195 auto rT2 = boost::posix_time::microsec_clock::local_time();
196 times_ms.push_back((rT2 - rT1).total_microseconds() * 1e-3);
198 print_stats(
"EIGEN3(double): MATRIX MULTIPLY", times_ms);
202 for (
int i = 0; i < num_trials; i++) {
203 Eigen::MatrixXd mat1 = Eigen::MatrixXd::Random(big_matrix_eigen1, big_matrix_eigen1);
204 auto rT1 = boost::posix_time::microsec_clock::local_time();
205 mat1 = mat1.inverse();
206 auto rT2 = boost::posix_time::microsec_clock::local_time();
207 times_ms.push_back((rT2 - rT1).total_microseconds() * 1e-3);
209 print_stats(
"EIGEN3(double): MATRIX INVERSION", times_ms);
213 for (
int i = 0; i < num_trials; i++) {
214 Eigen::MatrixXd mat1 = Eigen::MatrixXd::Random(big_matrix_eigen2, big_matrix_eigen1);
215 auto rT1 = boost::posix_time::microsec_clock::local_time();
216 Eigen::MatrixXd QR = mat1.householderQr().matrixQR();
217 auto rT2 = boost::posix_time::microsec_clock::local_time();
218 times_ms.push_back((rT2 - rT1).total_microseconds() * 1e-3);
220 print_stats(
"EIGEN3(double): HOUSEHOLDER QR FULL", times_ms);
224 for (
int i = 0; i < num_trials; i++) {
225 Eigen::MatrixXd mat1 = Eigen::MatrixXd::Random(big_matrix_eigen2, big_matrix_eigen1);
226 auto rT1 = boost::posix_time::microsec_clock::local_time();
227 Eigen::MatrixXd R = mat1.colPivHouseholderQr().matrixR();
228 auto rT2 = boost::posix_time::microsec_clock::local_time();
229 times_ms.push_back((rT2 - rT1).total_microseconds() * 1e-3);
231 print_stats(
"EIGEN3(double): HOUSEHOLDER QR PIV", times_ms);
235 for (
int i = 0; i < num_trials; i++) {
236 Eigen::MatrixXd mat1 = Eigen::MatrixXd::Random(big_matrix_eigen2, big_matrix_eigen1);
237 Eigen::VectorXd tempV1 = Eigen::VectorXd::Zero(big_matrix_eigen2 * big_matrix_eigen1, 1);
238 Eigen::VectorXd tempV2;
239 auto rT1 = boost::posix_time::microsec_clock::local_time();
240 for (
int k = 0; k < mat1.cols(); k++) {
241 int rows_left = mat1.rows() - k;
243 mat1.col(k).segment(k, rows_left).makeHouseholder(tempV2, tau, beta);
244 mat1.block(k, k, rows_left, mat1.cols() - k).applyHouseholderOnTheLeft(tempV2, tau, tempV1.data());
246 auto rT2 = boost::posix_time::microsec_clock::local_time();
247 times_ms.push_back((rT2 - rT1).total_microseconds() * 1e-3);
249 print_stats(
"EIGEN3(double): HOUSEHOLDER QR CUSTOM", times_ms);
257 for (
int i = 0; i < num_trials; i++) {
258 auto rT1 = boost::posix_time::microsec_clock::local_time();
259 Eigen::MatrixXf mat1 = Eigen::MatrixXf::Random(big_matrix_eigen1, big_matrix_eigen1);
260 Eigen::MatrixXf mat2 = Eigen::MatrixXf::Random(big_matrix_eigen1, big_matrix_eigen1);
261 auto rT2 = boost::posix_time::microsec_clock::local_time();
262 times_ms.push_back((rT2 - rT1).total_microseconds() * 1e-3);
264 print_stats(
"EIGEN3(float): RANDOM BIG MATRIX", times_ms);
268 for (
int i = 0; i < num_trials; i++) {
269 Eigen::MatrixXf mat1 = Eigen::MatrixXf::Random(big_matrix_eigen1, big_matrix_eigen1);
270 Eigen::MatrixXf mat2 = Eigen::MatrixXf::Random(big_matrix_eigen1, big_matrix_eigen1);
271 auto rT1 = boost::posix_time::microsec_clock::local_time();
272 Eigen::MatrixXf mat3 = mat1 * mat2;
273 auto rT2 = boost::posix_time::microsec_clock::local_time();
274 times_ms.push_back((rT2 - rT1).total_microseconds() * 1e-3);
276 print_stats(
"EIGEN3(float): MATRIX MULTIPLY", times_ms);
280 for (
int i = 0; i < num_trials; i++) {
281 Eigen::MatrixXf mat1 = Eigen::MatrixXf::Random(big_matrix_eigen1, big_matrix_eigen1);
282 auto rT1 = boost::posix_time::microsec_clock::local_time();
283 mat1 = mat1.inverse();
284 auto rT2 = boost::posix_time::microsec_clock::local_time();
285 times_ms.push_back((rT2 - rT1).total_microseconds() * 1e-3);
287 print_stats(
"EIGEN3(float): MATRIX INVERSION", times_ms);
291 Eigen::MatrixXf mat1 = Eigen::MatrixXf::Random(big_matrix_eigen2, big_matrix_eigen1);
292 for (
int i = 0; i < num_trials; i++) {
293 auto rT1 = boost::posix_time::microsec_clock::local_time();
294 Eigen::MatrixXf Q = mat1.householderQr().householderQ();
295 Eigen::MatrixXf R = Q.transpose() * mat1;
296 auto rT2 = boost::posix_time::microsec_clock::local_time();
297 times_ms.push_back((rT2 - rT1).total_microseconds() * 1e-3);
299 print_stats(
"EIGEN3(float): HOUSEHOLDER QR FULL", times_ms);
303 for (
int i = 0; i < num_trials; i++) {
304 Eigen::MatrixXf mat1 = Eigen::MatrixXf::Random(big_matrix_eigen2, big_matrix_eigen1);
305 auto rT1 = boost::posix_time::microsec_clock::local_time();
306 Eigen::MatrixXf R = mat1.colPivHouseholderQr().matrixR().triangularView<Eigen::Upper>();
307 auto rT2 = boost::posix_time::microsec_clock::local_time();
308 times_ms.push_back((rT2 - rT1).total_microseconds() * 1e-3);
310 print_stats(
"EIGEN3(float): HOUSEHOLDER QR PIV", times_ms);
314 for (
int i = 0; i < num_trials; i++) {
315 Eigen::MatrixXf mat1 = Eigen::MatrixXf::Random(big_matrix_eigen2, big_matrix_eigen1);
316 Eigen::VectorXf tempV1 = Eigen::VectorXf::Zero(big_matrix_eigen2 * big_matrix_eigen1, 1);
317 Eigen::VectorXf tempV2;
318 auto rT1 = boost::posix_time::microsec_clock::local_time();
319 for (
int k = 0; k < mat1.cols(); k++) {
320 int rows_left = mat1.rows() - k;
322 mat1.col(k).segment(k, rows_left).makeHouseholder(tempV2, tau, beta);
323 mat1.block(k, k, rows_left, mat1.cols() - k).applyHouseholderOnTheLeft(tempV2, tau, tempV1.data());
325 auto rT2 = boost::posix_time::microsec_clock::local_time();
326 times_ms.push_back((rT2 - rT1).total_microseconds() * 1e-3);
328 print_stats(
"EIGEN3(float): HOUSEHOLDER QR CUSTOM", times_ms);