diff --git a/vSLAM/ch5/joinMap/.kdev4/joinMap.kdev4 b/vSLAM/ch5/joinMap/.kdev4/joinMap.kdev4 index 2022e32b..eb72c3f4 100644 --- a/vSLAM/ch5/joinMap/.kdev4/joinMap.kdev4 +++ b/vSLAM/ch5/joinMap/.kdev4/joinMap.kdev4 @@ -24,8 +24,15 @@ Name=joinMap Type=Native Application [Launch][Launch Configuration 0][Data] +Arguments=../pose.txt Configured from ProjectItem=joinMap,joinMap +Dependencies=@Variant(\x00\x00\x00\t\x00\x00\x00\x00\x00) +Dependency Action=Nothing +EnvironmentGroup=default +Executable=file:///home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch5/joinMap/ +External Terminal=konsole --noclose --workdir %workdir -e %exe Project Target=joinMap,joinMap +Use External Terminal=false Working Directory=file:///home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch5/joinMap/build/ isExecutable=false diff --git a/vSLAM/ch5/joinMap/build/CMakeFiles/joinMap.dir/CXX.includecache b/vSLAM/ch5/joinMap/build/CMakeFiles/joinMap.dir/CXX.includecache index d402ba3a..bdce9121 100644 --- a/vSLAM/ch5/joinMap/build/CMakeFiles/joinMap.dir/CXX.includecache +++ b/vSLAM/ch5/joinMap/build/CMakeFiles/joinMap.dir/CXX.includecache @@ -11,6 +11,8 @@ iostream - fstream - +cstdlib +- opencv2/core/core.hpp - opencv2/highgui/highgui.hpp diff --git a/vSLAM/ch5/joinMap/build/CMakeFiles/joinMap.dir/joinMap.cpp.o b/vSLAM/ch5/joinMap/build/CMakeFiles/joinMap.dir/joinMap.cpp.o index 413df57a..f1ee1f57 100644 Binary files a/vSLAM/ch5/joinMap/build/CMakeFiles/joinMap.dir/joinMap.cpp.o and b/vSLAM/ch5/joinMap/build/CMakeFiles/joinMap.dir/joinMap.cpp.o differ diff --git a/vSLAM/ch5/joinMap/build/joinMap b/vSLAM/ch5/joinMap/build/joinMap index 350e8e4d..7708094c 100755 Binary files a/vSLAM/ch5/joinMap/build/joinMap and b/vSLAM/ch5/joinMap/build/joinMap differ diff --git a/vSLAM/ch5/joinMap/build/map.pcd b/vSLAM/ch5/joinMap/build/map.pcd new file mode 100644 index 00000000..ed8b3154 Binary files /dev/null and b/vSLAM/ch5/joinMap/build/map.pcd differ diff --git a/vSLAM/ch5/joinMap/joinMap.cpp b/vSLAM/ch5/joinMap/joinMap.cpp index 5d2f3222..7bdec3b2 100644 --- a/vSLAM/ch5/joinMap/joinMap.cpp +++ b/vSLAM/ch5/joinMap/joinMap.cpp @@ -1,5 +1,6 @@ -#include -#include +#include //字符io流 +#include //文件流 +#include //命令行调用 using namespace std; #include #include @@ -43,20 +44,23 @@ int main( int argc, char** argv ) -1.55819 -0.301094 1.6215 -0.02707 -0.250946 -0.0412848 0.966741 分别为五张图相机的位置和姿态 */ - ifstream fin("pose.txt"); + // ifstream fin("pose.txt"); + ifstream fin(argv[1]);//命令行加入参数 ../pose.txt if (!fin) { cerr<<"请在有pose.txt的目录下运行此程序"<>d; Eigen::Quaterniond q( data[6], data[3], data[4], data[5] );//data[6]为四元数实部 @@ -81,12 +85,14 @@ int main( int argc, char** argv ) // 新建一个点云 PointCloud::Ptr pointCloud( new PointCloud ); - for ( int i=0; i<5; i++ ) + for ( int i=0; i<5; i++ )//5张图像对 { cout<<"转换图像中: "<size()<<"个点."<头中,C++则为头),可以用来调用终端命令。 + system("pcl_viewer map.pcd"); return 0; } diff --git a/vSLAM/ch7/build/CMakeFiles/pose_estimation_2d2d.dir/pose_estimation_2d2d.cpp.o b/vSLAM/ch7/build/CMakeFiles/pose_estimation_2d2d.dir/pose_estimation_2d2d.cpp.o index 87c7f700..5c4655fe 100644 Binary files a/vSLAM/ch7/build/CMakeFiles/pose_estimation_2d2d.dir/pose_estimation_2d2d.cpp.o and b/vSLAM/ch7/build/CMakeFiles/pose_estimation_2d2d.dir/pose_estimation_2d2d.cpp.o differ diff --git a/vSLAM/ch7/build/CMakeFiles/pose_estimation_3d2d.dir/pose_estimation_3d2d.cpp.o b/vSLAM/ch7/build/CMakeFiles/pose_estimation_3d2d.dir/pose_estimation_3d2d.cpp.o index 6b1e0038..a439ac09 100644 Binary files a/vSLAM/ch7/build/CMakeFiles/pose_estimation_3d2d.dir/pose_estimation_3d2d.cpp.o and b/vSLAM/ch7/build/CMakeFiles/pose_estimation_3d2d.dir/pose_estimation_3d2d.cpp.o differ diff --git a/vSLAM/ch7/build/CMakeFiles/pose_estimation_3d3d.dir/pose_estimation_3d3d.cpp.o b/vSLAM/ch7/build/CMakeFiles/pose_estimation_3d3d.dir/pose_estimation_3d3d.cpp.o index f3d44146..f1ecc511 100644 Binary files a/vSLAM/ch7/build/CMakeFiles/pose_estimation_3d3d.dir/pose_estimation_3d3d.cpp.o and b/vSLAM/ch7/build/CMakeFiles/pose_estimation_3d3d.dir/pose_estimation_3d3d.cpp.o differ diff --git a/vSLAM/ch7/build/pose_estimation_2d2d b/vSLAM/ch7/build/pose_estimation_2d2d index 01265b4e..397adc48 100755 Binary files a/vSLAM/ch7/build/pose_estimation_2d2d and b/vSLAM/ch7/build/pose_estimation_2d2d differ diff --git a/vSLAM/ch7/build/pose_estimation_3d2d b/vSLAM/ch7/build/pose_estimation_3d2d index db19b966..b4a761e1 100755 Binary files a/vSLAM/ch7/build/pose_estimation_3d2d and b/vSLAM/ch7/build/pose_estimation_3d2d differ diff --git a/vSLAM/ch7/build/pose_estimation_3d3d b/vSLAM/ch7/build/pose_estimation_3d3d index a072b2aa..2840f2e3 100755 Binary files a/vSLAM/ch7/build/pose_estimation_3d3d and b/vSLAM/ch7/build/pose_estimation_3d3d differ diff --git a/vSLAM/ch7/feature_extraction.cpp b/vSLAM/ch7/feature_extraction.cpp index ae8b4571..ca02a1ae 100644 --- a/vSLAM/ch7/feature_extraction.cpp +++ b/vSLAM/ch7/feature_extraction.cpp @@ -25,11 +25,14 @@ int main ( int argc, char** argv ) //-- 初始化 std::vector keypoints_1, keypoints_2;//关键点 Mat descriptors_1, descriptors_2; //关键点对应的描述子 - Ptr detector = ORB::create(); //cv下 特征检测 - Ptr descriptor = ORB::create();//cv下 描述子 + Ptr detector = ORB::create(); //cv3下 特征检测 + Ptr descriptor = ORB::create();//cv3下 描述子 // Ptr detector = FeatureDetector::create(detector_name); // Ptr descriptor = DescriptorExtractor::create(descriptor_name); - Ptr matcher = DescriptorMatcher::create ( "BruteForce-Hamming" );//汉明 + // use this if you are in OpenCV2 + // Ptr detector = FeatureDetector::create ( "ORB" ); + // Ptr descriptor = DescriptorExtractor::create ( "ORB" ); + Ptr matcher = DescriptorMatcher::create ( "BruteForce-Hamming" );//汉明点对匹配 //-- 第一步:检测 Oriented FAST 角点位置 detector->detect ( img_1,keypoints_1 ); diff --git a/vSLAM/ch7/pose_estimation_2d2d.cpp b/vSLAM/ch7/pose_estimation_2d2d.cpp index 5ccf900f..8408df98 100644 --- a/vSLAM/ch7/pose_estimation_2d2d.cpp +++ b/vSLAM/ch7/pose_estimation_2d2d.cpp @@ -1,22 +1,26 @@ +/* + *对极几何 求解 两组单目相机 2D图像 + */ #include #include #include #include #include // #include "extra.h" // use this if in OpenCV2 -using namespace std; -using namespace cv; +using namespace std;//标准库 命名空间 +using namespace cv; //opencv库命名空间 +// ./pose_estimation_2d2d 1.png 2.png /**************************************************** - * 本程序演示了如何使用2D-2D的特征匹配估计相机运动 + * 本程序演示了如何使用2D-2D的特征匹配估计相机运动 * **************************************************/ - +//特征匹配 计算匹配点对 void find_feature_matches ( const Mat& img_1, const Mat& img_2, std::vector& keypoints_1, std::vector& keypoints_2, std::vector< DMatch >& matches ); - +//位置估计 计算旋转和平移 void pose_estimation_2d2d ( std::vector keypoints_1, std::vector keypoints_2, @@ -28,22 +32,22 @@ Point2d pixel2cam ( const Point2d& p, const Mat& K ); int main ( int argc, char** argv ) { - if ( argc != 3 ) + if ( argc != 3 )//命令行参数  1.png  2.png { cout<<"usage: pose_estimation_2d2d img1 img2"< keypoints_1, keypoints_2; - vector matches; - find_feature_matches ( img_1, img_2, keypoints_1, keypoints_2, matches ); + vector keypoints_1, keypoints_2;//关键点 + vector matches;//特征点匹配对 + find_feature_matches ( img_1, img_2, keypoints_1, keypoints_2, matches );//得到匹配点对 cout<<"一共找到了"< descriptor = DescriptorExtractor::create ( "ORB" ); - Ptr matcher = DescriptorMatcher::create ( "BruteForce-Hamming" ); - //-- 第一步:检测 Oriented FAST 角点位置 + Ptr matcher = DescriptorMatcher::create ( "BruteForce-Hamming" );//汉明点对匹配 + + //------------------第一步:检测 Oriented FAST 角点位置----------------------------- detector->detect ( img_1,keypoints_1 ); detector->detect ( img_2,keypoints_2 ); - //-- 第二步:根据角点位置计算 BRIEF 描述子 + //------------------第二步:根据角点位置计算 BRIEF 描述子------------------------- descriptor->compute ( img_1, keypoints_1, descriptors_1 ); descriptor->compute ( img_2, keypoints_2, descriptors_2 ); - //-- 第三步:对两幅图像中的BRIEF描述子进行匹配,使用 Hamming 距离 + //------------------第三步:对两幅图像中的BRIEF描述子进行匹配,使用 Hamming 距离 vector match; //BFMatcher matcher ( NORM_HAMMING ); - matcher->match ( descriptors_1, descriptors_2, match ); + matcher->match ( descriptors_1, descriptors_2, match );//各个特征点描述子之间的汉明距离匹配 - //-- 第四步:匹配点对筛选 + //-----------------第四步:匹配点对筛选-------------------------------------------------- double min_dist=10000, max_dist=0; - //找出所有匹配之间的最小距离和最大距离, 即是最相似的和最不相似的两组点之间的距离 for ( int i = 0; i < descriptors_1.rows; i++ ) { - double dist = match[i].distance; - if ( dist < min_dist ) min_dist = dist; - if ( dist > max_dist ) max_dist = dist; + double dist = matches[i].distance; + if ( dist < min_dist ) min_dist = dist; //最短距离 最相似 + if ( dist > max_dist ) max_dist = dist; //最长距离 最不相似 } - printf ( "-- Max dist : %f \n", max_dist ); printf ( "-- Min dist : %f \n", min_dist ); - //当描述子之间的距离大于两倍的最小距离时,即认为匹配有误.但有时候最小距离会非常小,设置一个经验值30作为下限. for ( int i = 0; i < descriptors_1.rows; i++ ) { @@ -119,7 +123,7 @@ void find_feature_matches ( const Mat& img_1, const Mat& img_2, } } - +// 像素坐标转相机归一化坐标 Point2d pixel2cam ( const Point2d& p, const Mat& K ) { return Point2d @@ -129,7 +133,8 @@ Point2d pixel2cam ( const Point2d& p, const Mat& K ) ); } - +//特征匹配 计算匹配点对 函数 第一张图 到第二章图的坐标变换矩阵和平移矩阵 +//对极几何 void pose_estimation_2d2d ( std::vector keypoints_1, std::vector keypoints_2, std::vector< DMatch > matches, @@ -138,34 +143,33 @@ void pose_estimation_2d2d ( std::vector keypoints_1, // 相机内参,TUM Freiburg2 Mat K = ( Mat_ ( 3,3 ) << 520.9, 0, 325.1, 0, 521.0, 249.7, 0, 0, 1 ); - //-- 把匹配点转换为vector的形式 + //------------把匹配点转换为vector的形式------------------ vector points1; vector points2; - for ( int i = 0; i < ( int ) matches.size(); i++ ) { points1.push_back ( keypoints_1[matches[i].queryIdx].pt ); points2.push_back ( keypoints_2[matches[i].trainIdx].pt ); } - //-- 计算基础矩阵 + //-----------计算基础矩阵----------------------------------------------------- Mat fundamental_matrix; fundamental_matrix = findFundamentalMat ( points1, points2, CV_FM_8POINT ); - cout<<"fundamental_matrix is "< #include #include @@ -11,11 +12,12 @@ #include #include #include -#include +#include //时间计时 -using namespace std; -using namespace cv; +using namespace std;//标准库 命名空间 +using namespace cv; //opencv库命名空间 +//特征匹配 计算匹配点对 void find_feature_matches ( const Mat& img_1, const Mat& img_2, std::vector& keypoints_1, @@ -25,6 +27,7 @@ void find_feature_matches ( // 像素坐标转相机归一化坐标 Point2d pixel2cam ( const Point2d& p, const Mat& K ); +//g2o_BundleAdjustment 优化 void bundleAdjustment ( const vector points_3d, const vector points_2d, @@ -34,7 +37,7 @@ void bundleAdjustment ( int main ( int argc, char** argv ) { - if ( argc != 5 ) + if ( argc != 5 )// 命令行参数 img1 img2 depth1 depth2 { cout<<"usage: pose_estimation_3d2d img1 img2 depth1 depth2"< keypoints_1, keypoints_2; - vector matches; + vector keypoints_1, keypoints_2;//关键点 + vector matches;//特征点匹配对 find_feature_matches ( img_1, img_2, keypoints_1, keypoints_2, matches ); cout<<"一共找到了"< ( 3,3 ) << 520.9, 0, 325.1, 0, 521.0, 249.7, 0, 0, 1 ); + Mat K = ( Mat_ ( 3,3 ) << 520.9, 0, 325.1, 0, 521.0, 249.7, 0, 0, 1 );// 相机内参,TUM Freiburg2 vector pts_3d; vector pts_2d; for ( DMatch m:matches ) @@ -59,7 +62,7 @@ int main ( int argc, char** argv ) if ( d == 0 ) // bad depth continue; float dd = d/1000.0; - Point2d p1 = pixel2cam ( keypoints_1[m.queryIdx].pt, K ); + Point2d p1 = pixel2cam ( keypoints_1[m.queryIdx].pt, K );// 像素坐标转相机归一化坐标 pts_3d.push_back ( Point3f ( p1.x*dd, p1.y*dd, dd ) ); pts_2d.push_back ( keypoints_2[m.trainIdx].pt ); } @@ -71,25 +74,26 @@ int main ( int argc, char** argv ) Mat R; cv::Rodrigues ( r, R ); // r为旋转向量形式,用Rodrigues公式转换为矩阵 - cout<<"R="<& keypoints_1, std::vector& keypoints_2, std::vector< DMatch >& matches ) { - //-- 初始化 - Mat descriptors_1, descriptors_2; - // used in OpenCV3 + //--------------------第0步:初始化------------------------------------------------------ + Mat descriptors_1, descriptors_2;//描述子 + // OpenCV3 特征点检测器 描述子生成器 用法 Ptr detector = ORB::create(); Ptr descriptor = ORB::create(); - // use this if you are in OpenCV2 + // OpenCV2 特征点检测器 描述子生成器 用法 // Ptr detector = FeatureDetector::create ( "ORB" ); // Ptr descriptor = DescriptorExtractor::create ( "ORB" ); Ptr matcher = DescriptorMatcher::create ( "BruteForce-Hamming" ); @@ -130,6 +134,7 @@ void find_feature_matches ( const Mat& img_1, const Mat& img_2, } } +// 像素坐标转相机归一化坐标 Point2d pixel2cam ( const Point2d& p, const Mat& K ) { return Point2d @@ -138,7 +143,7 @@ Point2d pixel2cam ( const Point2d& p, const Mat& K ) ( p.y - K.at ( 1,2 ) ) / K.at ( 1,1 ) ); } - +// g2o_BundleAdjustment 优化 void bundleAdjustment ( const vector< Point3f > points_3d, const vector< Point2f > points_2d, diff --git a/vSLAM/ch7/pose_estimation_3d3d.cpp b/vSLAM/ch7/pose_estimation_3d3d.cpp index 9c8e2696..c938e706 100644 --- a/vSLAM/ch7/pose_estimation_3d3d.cpp +++ b/vSLAM/ch7/pose_estimation_3d3d.cpp @@ -1,3 +1,7 @@ +/* + * 迭代最近点 Iterative Closest Point, ICP求解 3D坐标 到 3D坐标的转换矩阵(不用求解距离 激光SLAM 以及 RGB-D SLAM) + * 使用 线性代数SVD奇异值分解 或者 非线性优化方法 求解 + */ #include #include #include @@ -12,11 +16,12 @@ #include #include #include -#include +#include //算法计时 -using namespace std; -using namespace cv; +using namespace std;//标准库 命名空间 +using namespace cv; //opencv库命名空间 +//特征匹配 计算匹配点对 void find_feature_matches ( const Mat& img_1, const Mat& img_2, std::vector& keypoints_1, @@ -26,12 +31,14 @@ void find_feature_matches ( // 像素坐标转相机归一化坐标 Point2d pixel2cam ( const Point2d& p, const Mat& K ); +//ICP求解 3D坐标 到 3D坐标的转换矩阵 使用 线性代数SVD奇异值分解 void pose_estimation_3d3d ( const vector& pts1, const vector& pts2, Mat& R, Mat& t ); +//g2o_BundleAdjustment 优化 非线性优化方法 求解 void bundleAdjustment( const vector& points_3d, const vector& points_2d, @@ -51,7 +58,7 @@ class EdgeProjectXYZRGBDPoseOnly : public g2o::BaseUnaryEdge<3, Eigen::Vector3d, // measurement is p, point is p' _error = _measurement - pose->estimate().map( _point ); } - + // 3d-3d自定义求解器 virtual void linearizeOplus() { g2o::VertexSE3Expmap* pose = static_cast(_vertices[0]); @@ -60,7 +67,7 @@ class EdgeProjectXYZRGBDPoseOnly : public g2o::BaseUnaryEdge<3, Eigen::Vector3d, double x = xyz_trans[0]; double y = xyz_trans[1]; double z = xyz_trans[2]; - + // 3×6的雅克比矩阵 _jacobianOplusXi(0,0) = 0; _jacobianOplusXi(0,1) = -z; _jacobianOplusXi(0,2) = y; @@ -108,7 +115,7 @@ int main ( int argc, char** argv ) // 建立3D点 Mat depth1 = imread ( argv[3], CV_LOAD_IMAGE_UNCHANGED ); // 深度图为16位无符号数,单通道图像 Mat depth2 = imread ( argv[4], CV_LOAD_IMAGE_UNCHANGED ); // 深度图为16位无符号数,单通道图像 - Mat K = ( Mat_ ( 3,3 ) << 520.9, 0, 325.1, 0, 521.0, 249.7, 0, 0, 1 ); + Mat K = ( Mat_ ( 3,3 ) << 520.9, 0, 325.1, 0, 521.0, 249.7, 0, 0, 1 );// 相机内参,TUM Freiburg2 vector pts1, pts2; for ( DMatch m:matches ) @@ -127,18 +134,19 @@ int main ( int argc, char** argv ) cout<<"3d-3d pairs: "<& keypoints_1, std::vector& keypoints_2, std::vector< DMatch >& matches ); +//位置估计 计算旋转和平移 第一张图 到第二章图的坐标变换矩阵和平移矩阵 void pose_estimation_2d2d ( const std::vector& keypoints_1, const std::vector& keypoints_2, const std::vector< DMatch >& matches, Mat& R, Mat& t ); +// 三角测量 void triangulation ( const vector& keypoint_1, const vector& keypoint_2, @@ -32,22 +42,22 @@ Point2f pixel2cam( const Point2d& p, const Mat& K ); int main ( int argc, char** argv ) { - if ( argc != 3 ) + if ( argc != 3 )//命令行参数  1.png  2.png { cout<<"usage: triangulation img1 img2"< keypoints_1, keypoints_2; - vector matches; + vector keypoints_1, keypoints_2;//关键点 + vector matches;//特征点匹配对 find_feature_matches ( img_1, img_2, keypoints_1, keypoints_2, matches ); cout<<"一共找到了"< ( 3,3 ) << 520.9, 0, 325.1, 0, 521.0, 249.7, 0, 0, 1 ); + Mat K = ( Mat_ ( 3,3 ) << 520.9, 0, 325.1, 0, 521.0, 249.7, 0, 0, 1 );// 相机内参,TUM Freiburg2 for ( int i=0; i& keypoints_1, std::vector& keypoints_2, std::vector< DMatch >& matches ) { - //-- 初始化 - Mat descriptors_1, descriptors_2; - // used in OpenCV3 + //--------------------第0步:初始化------------------------------------------------------ + Mat descriptors_1, descriptors_2;//描述子 + // OpenCV3 特征点检测器 描述子生成器 用法 Ptr detector = ORB::create(); Ptr descriptor = ORB::create(); - // use this if you are in OpenCV2 + // OpenCV2 特征点检测器 描述子生成器 用法 // Ptr detector = FeatureDetector::create ( "ORB" ); // Ptr descriptor = DescriptorExtractor::create ( "ORB" ); - Ptr matcher = DescriptorMatcher::create("BruteForce-Hamming"); - //-- 第一步:检测 Oriented FAST 角点位置 + Ptr matcher = DescriptorMatcher::create("BruteForce-Hamming");;//汉明点对匹配 + + //------------------第一步:检测 Oriented FAST 角点位置----------------------------- detector->detect ( img_1,keypoints_1 ); detector->detect ( img_2,keypoints_2 ); - //-- 第二步:根据角点位置计算 BRIEF 描述子 + //------------------第二步:根据角点位置计算 BRIEF 描述子------------------------- descriptor->compute ( img_1, keypoints_1, descriptors_1 ); descriptor->compute ( img_2, keypoints_2, descriptors_2 ); - //-- 第三步:对两幅图像中的BRIEF描述子进行匹配,使用 Hamming 距离 + //------------------第三步:对两幅图像中的BRIEF描述子进行匹配,使用 Hamming 距离 vector match; // BFMatcher matcher ( NORM_HAMMING ); matcher->match ( descriptors_1, descriptors_2, match ); - //-- 第四步:匹配点对筛选 + //-----------------第四步:匹配点对筛选-------------------------------------------------- double min_dist=10000, max_dist=0; //找出所有匹配之间的最小距离和最大距离, 即是最相似的和最不相似的两组点之间的距离 for ( int i = 0; i < descriptors_1.rows; i++ ) { double dist = match[i].distance; - if ( dist < min_dist ) min_dist = dist; - if ( dist > max_dist ) max_dist = dist; + if ( dist < min_dist ) min_dist = dist; //最短距离 最相似 + if ( dist > max_dist ) max_dist = dist; //最长距离 最不相似 } printf ( "-- Max dist : %f \n", max_dist ); @@ -130,6 +142,8 @@ void find_feature_matches ( const Mat& img_1, const Mat& img_2, } } +//特征匹配 计算匹配点对 函数 第一张图 到第二章图的坐标变换矩阵和平移矩阵 +//对极几何 void pose_estimation_2d2d ( const std::vector& keypoints_1, const std::vector& keypoints_2, @@ -172,11 +186,13 @@ void pose_estimation_2d2d ( cout<<"t is "<& keypoint_1, const vector< KeyPoint >& keypoint_2, const std::vector< DMatch >& matches, - const Mat& R, const Mat& t, + const Mat& R, const Mat& t, //特征匹配 计算匹配点对 函数 第一张图 到第二章图的坐标变换矩阵和平移矩阵 +//对极几何 vector< Point3d >& points ) { Mat T1 = (Mat_ (3,4) << @@ -189,7 +205,7 @@ void triangulation ( R.at(2,0), R.at(2,1), R.at(2,2), t.at(2,0) ); - Mat K = ( Mat_ ( 3,3 ) << 520.9, 0, 325.1, 0, 521.0, 249.7, 0, 0, 1 ); + Mat K = ( Mat_ ( 3,3 ) << 520.9, 0, 325.1, 0, 521.0, 249.7, 0, 0, 1 );// 相机内参,TUM Freiburg2 vector pts_1, pts_2; for ( DMatch m:matches ) { @@ -215,6 +231,7 @@ void triangulation ( } } +// 像素坐标转相机归一化坐标 Point2f pixel2cam ( const Point2d& p, const Mat& K ) { return Point2f diff --git a/vSLAM/ch8/LKFlow/.kdev4/LKFlow.kdev4 b/vSLAM/ch8/LKFlow/.kdev4/LKFlow.kdev4 new file mode 100644 index 00000000..d2d332a0 --- /dev/null +++ b/vSLAM/ch8/LKFlow/.kdev4/LKFlow.kdev4 @@ -0,0 +1,18 @@ +[Buildset] +BuildItems=@Variant(\x00\x00\x00\t\x00\x00\x00\x00\x01\x00\x00\x00\x0b\x00\x00\x00\x00\x01\x00\x00\x00\x0c\x00L\x00K\x00F\x00l\x00o\x00w) + +[CMake] +Build Directory Count=1 +Current Build Directory Index=0 +ProjectRootRelative=./ + +[CMake][CMake Build Directory 0] +Build Directory Path=file:///home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build +Build Type=Debug +CMake Binary=file:///usr/bin/cmake +Environment Profile= +Extra Arguments= +Install Directory=file:///usr/local + +[Project] +VersionControlSupport=kdevgit diff --git a/vSLAM/ch8/LKFlow/LKFlow.kdev4 b/vSLAM/ch8/LKFlow/LKFlow.kdev4 new file mode 100644 index 00000000..0f65b686 --- /dev/null +++ b/vSLAM/ch8/LKFlow/LKFlow.kdev4 @@ -0,0 +1,3 @@ +[Project] +Manager=KDevCMakeManager +Name=LKFlow diff --git a/vSLAM/ch8/LKFlow/build/CMakeCache.txt b/vSLAM/ch8/LKFlow/build/CMakeCache.txt new file mode 100644 index 00000000..89265ea0 --- /dev/null +++ b/vSLAM/ch8/LKFlow/build/CMakeCache.txt @@ -0,0 +1,338 @@ +# This is the CMakeCache file. +# For build in directory: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build +# It was generated by CMake: /usr/bin/cmake +# You can edit this file to change values found and used by cmake. +# If you do not want to change any of the values, simply exit the editor. +# If you do want to change a value, simply edit, save, and exit the editor. +# The syntax for the file is as follows: +# KEY:TYPE=VALUE +# KEY is the name of a variable in the cache. +# TYPE is a hint to GUIs for the type of VALUE, DO NOT EDIT TYPE!. +# VALUE is the current value for the KEY. + +######################## +# EXTERNAL cache entries +######################## + +//Path to a program. +CMAKE_AR:FILEPATH=/usr/bin/ar + +//Choose the type of build, options are: None(CMAKE_CXX_FLAGS or +// CMAKE_C_FLAGS used) Debug Release RelWithDebInfo MinSizeRel. +CMAKE_BUILD_TYPE:STRING=Debug + +//Enable/Disable color output during build. +CMAKE_COLOR_MAKEFILE:BOOL=ON + +//CXX compiler. +CMAKE_CXX_COMPILER:FILEPATH=/usr/bin/c++ + +//Flags used by the compiler during all build types. +CMAKE_CXX_FLAGS:STRING= + +//Flags used by the compiler during debug builds. +CMAKE_CXX_FLAGS_DEBUG:STRING=-g + +//Flags used by the compiler during release minsize builds. +CMAKE_CXX_FLAGS_MINSIZEREL:STRING=-Os -DNDEBUG + +//Flags used by the compiler during release builds (/MD /Ob1 /Oi +// /Ot /Oy /Gs will produce slightly less optimized but smaller +// files). +CMAKE_CXX_FLAGS_RELEASE:STRING=-O3 -DNDEBUG + +//Flags used by the compiler during Release with Debug Info builds. +CMAKE_CXX_FLAGS_RELWITHDEBINFO:STRING=-O2 -g -DNDEBUG + +//C compiler. +CMAKE_C_COMPILER:FILEPATH=/usr/bin/cc + +//Flags used by the compiler during all build types. +CMAKE_C_FLAGS:STRING= + +//Flags used by the compiler during debug builds. +CMAKE_C_FLAGS_DEBUG:STRING=-g + +//Flags used by the compiler during release minsize builds. +CMAKE_C_FLAGS_MINSIZEREL:STRING=-Os -DNDEBUG + +//Flags used by the compiler during release builds (/MD /Ob1 /Oi +// /Ot /Oy /Gs will produce slightly less optimized but smaller +// files). +CMAKE_C_FLAGS_RELEASE:STRING=-O3 -DNDEBUG + +//Flags used by the compiler during Release with Debug Info builds. +CMAKE_C_FLAGS_RELWITHDEBINFO:STRING=-O2 -g -DNDEBUG + +//Flags used by the linker. +CMAKE_EXE_LINKER_FLAGS:STRING=' ' + +//Flags used by the linker during debug builds. +CMAKE_EXE_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during release minsize builds. +CMAKE_EXE_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during release builds. +CMAKE_EXE_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during Release with Debug Info builds. +CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//Enable/Disable output of compile commands during generation. +CMAKE_EXPORT_COMPILE_COMMANDS:BOOL=OFF + +//Install path prefix, prepended onto install directories. +CMAKE_INSTALL_PREFIX:PATH=/usr/local + +//Path to a program. +CMAKE_LINKER:FILEPATH=/usr/bin/ld + +//Path to a program. +CMAKE_MAKE_PROGRAM:FILEPATH=/usr/bin/make + +//Flags used by the linker during the creation of modules. +CMAKE_MODULE_LINKER_FLAGS:STRING=' ' + +//Flags used by the linker during debug builds. +CMAKE_MODULE_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during release minsize builds. +CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during release builds. +CMAKE_MODULE_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during Release with Debug Info builds. +CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//Path to a program. +CMAKE_NM:FILEPATH=/usr/bin/nm + +//Path to a program. +CMAKE_OBJCOPY:FILEPATH=/usr/bin/objcopy + +//Path to a program. +CMAKE_OBJDUMP:FILEPATH=/usr/bin/objdump + +//Value Computed by CMake +CMAKE_PROJECT_NAME:STATIC=useLK + +//Path to a program. +CMAKE_RANLIB:FILEPATH=/usr/bin/ranlib + +//Flags used by the linker during the creation of dll's. +CMAKE_SHARED_LINKER_FLAGS:STRING=' ' + +//Flags used by the linker during debug builds. +CMAKE_SHARED_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during release minsize builds. +CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during release builds. +CMAKE_SHARED_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during Release with Debug Info builds. +CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//If set, runtime paths are not added when installing shared libraries, +// but are added when building. +CMAKE_SKIP_INSTALL_RPATH:BOOL=NO + +//If set, runtime paths are not added when using shared libraries. +CMAKE_SKIP_RPATH:BOOL=NO + +//Flags used by the linker during the creation of static libraries. +CMAKE_STATIC_LINKER_FLAGS:STRING= + +//Flags used by the linker during debug builds. +CMAKE_STATIC_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during release minsize builds. +CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during release builds. +CMAKE_STATIC_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during Release with Debug Info builds. +CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//Path to a program. +CMAKE_STRIP:FILEPATH=/usr/bin/strip + +//If true, cmake will use relative paths in makefiles and projects. +CMAKE_USE_RELATIVE_PATHS:BOOL=OFF + +//If this value is on, makefiles will be generated without the +// .SILENT directive, and all commands will be echoed to the console +// during the make. This is useful for debugging only. With Visual +// Studio IDE projects all commands are done without /nologo. +CMAKE_VERBOSE_MAKEFILE:BOOL=FALSE + +//Path where debug 3rdparty OpenCV dependencies are located +OpenCV_3RDPARTY_LIB_DIR_DBG:PATH=/usr/local/share/OpenCV/3rdparty/lib + +//Path where release 3rdparty OpenCV dependencies are located +OpenCV_3RDPARTY_LIB_DIR_OPT:PATH=/usr/local/share/OpenCV/3rdparty/lib + +OpenCV_CONFIG_PATH:FILEPATH=/usr/local/share/OpenCV + +//The directory containing a CMake configuration file for OpenCV. +OpenCV_DIR:PATH=/usr/local/share/OpenCV + +//Path where debug OpenCV libraries are located +OpenCV_LIB_DIR_DBG:PATH= + +//Path where release OpenCV libraries are located +OpenCV_LIB_DIR_OPT:PATH= + +//Value Computed by CMake +useLK_BINARY_DIR:STATIC=/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build + +//Value Computed by CMake +useLK_SOURCE_DIR:STATIC=/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow + + +######################## +# INTERNAL cache entries +######################## + +//ADVANCED property for variable: CMAKE_AR +CMAKE_AR-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_BUILD_TOOL +CMAKE_BUILD_TOOL-ADVANCED:INTERNAL=1 +//What is the target build tool cmake is generating for. +CMAKE_BUILD_TOOL:INTERNAL=/usr/bin/make +//This is the directory where this CMakeCache.txt was created +CMAKE_CACHEFILE_DIR:INTERNAL=/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build +//Major version of cmake used to create the current loaded cache +CMAKE_CACHE_MAJOR_VERSION:INTERNAL=2 +//Minor version of cmake used to create the current loaded cache +CMAKE_CACHE_MINOR_VERSION:INTERNAL=8 +//Patch version of cmake used to create the current loaded cache +CMAKE_CACHE_PATCH_VERSION:INTERNAL=12 +//ADVANCED property for variable: CMAKE_COLOR_MAKEFILE +CMAKE_COLOR_MAKEFILE-ADVANCED:INTERNAL=1 +//Path to CMake executable. +CMAKE_COMMAND:INTERNAL=/usr/bin/cmake +//Path to cpack program executable. +CMAKE_CPACK_COMMAND:INTERNAL=/usr/bin/cpack +//Path to ctest program executable. +CMAKE_CTEST_COMMAND:INTERNAL=/usr/bin/ctest +//ADVANCED property for variable: CMAKE_CXX_COMPILER +CMAKE_CXX_COMPILER-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS +CMAKE_CXX_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_DEBUG +CMAKE_CXX_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_MINSIZEREL +CMAKE_CXX_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_RELEASE +CMAKE_CXX_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_RELWITHDEBINFO +CMAKE_CXX_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_COMPILER +CMAKE_C_COMPILER-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS +CMAKE_C_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS_DEBUG +CMAKE_C_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS_MINSIZEREL +CMAKE_C_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS_RELEASE +CMAKE_C_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS_RELWITHDEBINFO +CMAKE_C_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//Executable file format +CMAKE_EXECUTABLE_FORMAT:INTERNAL=ELF +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS +CMAKE_EXE_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_DEBUG +CMAKE_EXE_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_MINSIZEREL +CMAKE_EXE_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_RELEASE +CMAKE_EXE_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXPORT_COMPILE_COMMANDS +CMAKE_EXPORT_COMPILE_COMMANDS-ADVANCED:INTERNAL=1 +//Name of generator. +CMAKE_GENERATOR:INTERNAL=Unix Makefiles +//Name of generator toolset. +CMAKE_GENERATOR_TOOLSET:INTERNAL= +//Start directory with the top level CMakeLists.txt file for this +// project +CMAKE_HOME_DIRECTORY:INTERNAL=/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow +//Install .so files without execute permission. +CMAKE_INSTALL_SO_NO_EXE:INTERNAL=1 +//ADVANCED property for variable: CMAKE_LINKER +CMAKE_LINKER-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MAKE_PROGRAM +CMAKE_MAKE_PROGRAM-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS +CMAKE_MODULE_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_DEBUG +CMAKE_MODULE_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL +CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_RELEASE +CMAKE_MODULE_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_NM +CMAKE_NM-ADVANCED:INTERNAL=1 +//number of local generators +CMAKE_NUMBER_OF_LOCAL_GENERATORS:INTERNAL=1 +//ADVANCED property for variable: CMAKE_OBJCOPY +CMAKE_OBJCOPY-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_OBJDUMP +CMAKE_OBJDUMP-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_RANLIB +CMAKE_RANLIB-ADVANCED:INTERNAL=1 +//Path to CMake installation. +CMAKE_ROOT:INTERNAL=/usr/share/cmake-2.8 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS +CMAKE_SHARED_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_DEBUG +CMAKE_SHARED_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL +CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_RELEASE +CMAKE_SHARED_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SKIP_INSTALL_RPATH +CMAKE_SKIP_INSTALL_RPATH-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SKIP_RPATH +CMAKE_SKIP_RPATH-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS +CMAKE_STATIC_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_DEBUG +CMAKE_STATIC_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL +CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_RELEASE +CMAKE_STATIC_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STRIP +CMAKE_STRIP-ADVANCED:INTERNAL=1 +//uname command +CMAKE_UNAME:INTERNAL=/bin/uname +//ADVANCED property for variable: CMAKE_USE_RELATIVE_PATHS +CMAKE_USE_RELATIVE_PATHS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_VERBOSE_MAKEFILE +CMAKE_VERBOSE_MAKEFILE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: OpenCV_3RDPARTY_LIB_DIR_DBG +OpenCV_3RDPARTY_LIB_DIR_DBG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: OpenCV_3RDPARTY_LIB_DIR_OPT +OpenCV_3RDPARTY_LIB_DIR_OPT-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: OpenCV_CONFIG_PATH +OpenCV_CONFIG_PATH-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: OpenCV_LIB_DIR_DBG +OpenCV_LIB_DIR_DBG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: OpenCV_LIB_DIR_OPT +OpenCV_LIB_DIR_OPT-ADVANCED:INTERNAL=1 + diff --git a/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CMakeCCompiler.cmake b/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CMakeCCompiler.cmake new file mode 100644 index 00000000..f4a508be --- /dev/null +++ b/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CMakeCCompiler.cmake @@ -0,0 +1,56 @@ +set(CMAKE_C_COMPILER "/usr/bin/cc") +set(CMAKE_C_COMPILER_ARG1 "") +set(CMAKE_C_COMPILER_ID "GNU") +set(CMAKE_C_COMPILER_VERSION "4.8.4") +set(CMAKE_C_PLATFORM_ID "Linux") + +set(CMAKE_AR "/usr/bin/ar") +set(CMAKE_RANLIB "/usr/bin/ranlib") +set(CMAKE_LINKER "/usr/bin/ld") +set(CMAKE_COMPILER_IS_GNUCC 1) +set(CMAKE_C_COMPILER_LOADED 1) +set(CMAKE_C_COMPILER_WORKS TRUE) +set(CMAKE_C_ABI_COMPILED TRUE) +set(CMAKE_COMPILER_IS_MINGW ) +set(CMAKE_COMPILER_IS_CYGWIN ) +if(CMAKE_COMPILER_IS_CYGWIN) + set(CYGWIN 1) + set(UNIX 1) +endif() + +set(CMAKE_C_COMPILER_ENV_VAR "CC") + +if(CMAKE_COMPILER_IS_MINGW) + set(MINGW 1) +endif() +set(CMAKE_C_COMPILER_ID_RUN 1) +set(CMAKE_C_SOURCE_FILE_EXTENSIONS c) +set(CMAKE_C_IGNORE_EXTENSIONS h;H;o;O;obj;OBJ;def;DEF;rc;RC) +set(CMAKE_C_LINKER_PREFERENCE 10) + +# Save compiler ABI information. +set(CMAKE_C_SIZEOF_DATA_PTR "8") +set(CMAKE_C_COMPILER_ABI "ELF") +set(CMAKE_C_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") + +if(CMAKE_C_SIZEOF_DATA_PTR) + set(CMAKE_SIZEOF_VOID_P "${CMAKE_C_SIZEOF_DATA_PTR}") +endif() + +if(CMAKE_C_COMPILER_ABI) + set(CMAKE_INTERNAL_PLATFORM_ABI "${CMAKE_C_COMPILER_ABI}") +endif() + +if(CMAKE_C_LIBRARY_ARCHITECTURE) + set(CMAKE_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") +endif() + + + + +set(CMAKE_C_IMPLICIT_LINK_LIBRARIES "c") +set(CMAKE_C_IMPLICIT_LINK_DIRECTORIES "/usr/lib/gcc/x86_64-linux-gnu/4.8;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib") +set(CMAKE_C_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES "") + + + diff --git a/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake b/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake new file mode 100644 index 00000000..1ca40dbc --- /dev/null +++ b/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake @@ -0,0 +1,57 @@ +set(CMAKE_CXX_COMPILER "/usr/bin/c++") +set(CMAKE_CXX_COMPILER_ARG1 "") +set(CMAKE_CXX_COMPILER_ID "GNU") +set(CMAKE_CXX_COMPILER_VERSION "4.8.4") +set(CMAKE_CXX_PLATFORM_ID "Linux") + +set(CMAKE_AR "/usr/bin/ar") +set(CMAKE_RANLIB "/usr/bin/ranlib") +set(CMAKE_LINKER "/usr/bin/ld") +set(CMAKE_COMPILER_IS_GNUCXX 1) +set(CMAKE_CXX_COMPILER_LOADED 1) +set(CMAKE_CXX_COMPILER_WORKS TRUE) +set(CMAKE_CXX_ABI_COMPILED TRUE) +set(CMAKE_COMPILER_IS_MINGW ) +set(CMAKE_COMPILER_IS_CYGWIN ) +if(CMAKE_COMPILER_IS_CYGWIN) + set(CYGWIN 1) + set(UNIX 1) +endif() + +set(CMAKE_CXX_COMPILER_ENV_VAR "CXX") + +if(CMAKE_COMPILER_IS_MINGW) + set(MINGW 1) +endif() +set(CMAKE_CXX_COMPILER_ID_RUN 1) +set(CMAKE_CXX_IGNORE_EXTENSIONS inl;h;hpp;HPP;H;o;O;obj;OBJ;def;DEF;rc;RC) +set(CMAKE_CXX_SOURCE_FILE_EXTENSIONS C;M;c++;cc;cpp;cxx;m;mm;CPP) +set(CMAKE_CXX_LINKER_PREFERENCE 30) +set(CMAKE_CXX_LINKER_PREFERENCE_PROPAGATES 1) + +# Save compiler ABI information. +set(CMAKE_CXX_SIZEOF_DATA_PTR "8") +set(CMAKE_CXX_COMPILER_ABI "ELF") +set(CMAKE_CXX_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") + +if(CMAKE_CXX_SIZEOF_DATA_PTR) + set(CMAKE_SIZEOF_VOID_P "${CMAKE_CXX_SIZEOF_DATA_PTR}") +endif() + +if(CMAKE_CXX_COMPILER_ABI) + set(CMAKE_INTERNAL_PLATFORM_ABI "${CMAKE_CXX_COMPILER_ABI}") +endif() + +if(CMAKE_CXX_LIBRARY_ARCHITECTURE) + set(CMAKE_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") +endif() + + + + +set(CMAKE_CXX_IMPLICIT_LINK_LIBRARIES "stdc++;m;c") +set(CMAKE_CXX_IMPLICIT_LINK_DIRECTORIES "/usr/lib/gcc/x86_64-linux-gnu/4.8;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib") +set(CMAKE_CXX_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES "") + + + diff --git a/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_C.bin b/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_C.bin new file mode 100755 index 00000000..f909aaac Binary files /dev/null and b/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_C.bin differ diff --git a/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_CXX.bin b/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_CXX.bin new file mode 100755 index 00000000..d6b41c89 Binary files /dev/null and b/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_CXX.bin differ diff --git a/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CMakeSystem.cmake b/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CMakeSystem.cmake new file mode 100644 index 00000000..8444407c --- /dev/null +++ b/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CMakeSystem.cmake @@ -0,0 +1,15 @@ +set(CMAKE_HOST_SYSTEM "Linux-4.4.0-94-generic") +set(CMAKE_HOST_SYSTEM_NAME "Linux") +set(CMAKE_HOST_SYSTEM_VERSION "4.4.0-94-generic") +set(CMAKE_HOST_SYSTEM_PROCESSOR "x86_64") + + + +set(CMAKE_SYSTEM "Linux-4.4.0-94-generic") +set(CMAKE_SYSTEM_NAME "Linux") +set(CMAKE_SYSTEM_VERSION "4.4.0-94-generic") +set(CMAKE_SYSTEM_PROCESSOR "x86_64") + +set(CMAKE_CROSSCOMPILING "FALSE") + +set(CMAKE_SYSTEM_LOADED 1) diff --git a/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CompilerIdC/CMakeCCompilerId.c b/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CompilerIdC/CMakeCCompilerId.c new file mode 100644 index 00000000..cba81d4a --- /dev/null +++ b/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CompilerIdC/CMakeCCompilerId.c @@ -0,0 +1,389 @@ +#ifdef __cplusplus +# error "A C++ compiler has been selected for C." +#endif + +/* Version number components: V=Version, R=Revision, P=Patch + Version date components: YYYY=Year, MM=Month, DD=Day */ + +#if defined(__18CXX) +# define ID_VOID_MAIN +#endif + +#if defined(__INTEL_COMPILER) || defined(__ICC) +# define COMPILER_ID "Intel" + /* __INTEL_COMPILER = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER/100) +# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER % 10) +# if defined(__INTEL_COMPILER_BUILD_DATE) + /* __INTEL_COMPILER_BUILD_DATE = YYYYMMDD */ +# define COMPILER_VERSION_TWEAK DEC(__INTEL_COMPILER_BUILD_DATE) +# endif + +#elif defined(__PATHCC__) +# define COMPILER_ID "PathScale" +# define COMPILER_VERSION_MAJOR DEC(__PATHCC__) +# define COMPILER_VERSION_MINOR DEC(__PATHCC_MINOR__) +# if defined(__PATHCC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__PATHCC_PATCHLEVEL__) +# endif + +#elif defined(__clang__) +# define COMPILER_ID "Clang" +# define COMPILER_VERSION_MAJOR DEC(__clang_major__) +# define COMPILER_VERSION_MINOR DEC(__clang_minor__) +# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__) + +#elif defined(__BORLANDC__) && defined(__CODEGEARC_VERSION__) +# define COMPILER_ID "Embarcadero" +# define COMPILER_VERSION_MAJOR HEX(__CODEGEARC_VERSION__>>24 & 0x00FF) +# define COMPILER_VERSION_MINOR HEX(__CODEGEARC_VERSION__>>16 & 0x00FF) +# define COMPILER_VERSION_PATCH HEX(__CODEGEARC_VERSION__ & 0xFFFF) + +#elif defined(__BORLANDC__) +# define COMPILER_ID "Borland" + /* __BORLANDC__ = 0xVRR */ +# define COMPILER_VERSION_MAJOR HEX(__BORLANDC__>>8) +# define COMPILER_VERSION_MINOR HEX(__BORLANDC__ & 0xFF) + +#elif defined(__WATCOMC__) +# define COMPILER_ID "Watcom" + /* __WATCOMC__ = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(__WATCOMC__ / 100) +# define COMPILER_VERSION_MINOR DEC(__WATCOMC__ % 100) + +#elif defined(__SUNPRO_C) +# define COMPILER_ID "SunPro" +# if __SUNPRO_C >= 0x5100 + /* __SUNPRO_C = 0xVRRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_C>>12) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_C>>4 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_C & 0xF) +# else + /* __SUNPRO_C = 0xVRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_C>>8) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_C>>4 & 0xF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_C & 0xF) +# endif + +#elif defined(__HP_cc) +# define COMPILER_ID "HP" + /* __HP_cc = VVRRPP */ +# define COMPILER_VERSION_MAJOR DEC(__HP_cc/10000) +# define COMPILER_VERSION_MINOR DEC(__HP_cc/100 % 100) +# define COMPILER_VERSION_PATCH DEC(__HP_cc % 100) + +#elif defined(__DECC) +# define COMPILER_ID "Compaq" + /* __DECC_VER = VVRRTPPPP */ +# define COMPILER_VERSION_MAJOR DEC(__DECC_VER/10000000) +# define COMPILER_VERSION_MINOR DEC(__DECC_VER/100000 % 100) +# define COMPILER_VERSION_PATCH DEC(__DECC_VER % 10000) + +#elif defined(__IBMC__) +# if defined(__COMPILER_VER__) +# define COMPILER_ID "zOS" +# else +# if __IBMC__ >= 800 +# define COMPILER_ID "XL" +# else +# define COMPILER_ID "VisualAge" +# endif + /* __IBMC__ = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__IBMC__/100) +# define COMPILER_VERSION_MINOR DEC(__IBMC__/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__IBMC__ % 10) +# endif + +#elif defined(__PGI) +# define COMPILER_ID "PGI" +# define COMPILER_VERSION_MAJOR DEC(__PGIC__) +# define COMPILER_VERSION_MINOR DEC(__PGIC_MINOR__) +# if defined(__PGIC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__PGIC_PATCHLEVEL__) +# endif + +#elif defined(_CRAYC) +# define COMPILER_ID "Cray" +# define COMPILER_VERSION_MAJOR DEC(_RELEASE) +# define COMPILER_VERSION_MINOR DEC(_RELEASE_MINOR) + +#elif defined(__TI_COMPILER_VERSION__) +# define COMPILER_ID "TI" + /* __TI_COMPILER_VERSION__ = VVVRRRPPP */ +# define COMPILER_VERSION_MAJOR DEC(__TI_COMPILER_VERSION__/1000000) +# define COMPILER_VERSION_MINOR DEC(__TI_COMPILER_VERSION__/1000 % 1000) +# define COMPILER_VERSION_PATCH DEC(__TI_COMPILER_VERSION__ % 1000) + +#elif defined(__TINYC__) +# define COMPILER_ID "TinyCC" + +#elif defined(__SCO_VERSION__) +# define COMPILER_ID "SCO" + +#elif defined(__GNUC__) +# define COMPILER_ID "GNU" +# define COMPILER_VERSION_MAJOR DEC(__GNUC__) +# define COMPILER_VERSION_MINOR DEC(__GNUC_MINOR__) +# if defined(__GNUC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__) +# endif + +#elif defined(_MSC_VER) +# define COMPILER_ID "MSVC" + /* _MSC_VER = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(_MSC_VER / 100) +# define COMPILER_VERSION_MINOR DEC(_MSC_VER % 100) +# if defined(_MSC_FULL_VER) +# if _MSC_VER >= 1400 + /* _MSC_FULL_VER = VVRRPPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 100000) +# else + /* _MSC_FULL_VER = VVRRPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 10000) +# endif +# endif +# if defined(_MSC_BUILD) +# define COMPILER_VERSION_TWEAK DEC(_MSC_BUILD) +# endif + +/* Analog VisualDSP++ >= 4.5.6 */ +#elif defined(__VISUALDSPVERSION__) +# define COMPILER_ID "ADSP" + /* __VISUALDSPVERSION__ = 0xVVRRPP00 */ +# define COMPILER_VERSION_MAJOR HEX(__VISUALDSPVERSION__>>24) +# define COMPILER_VERSION_MINOR HEX(__VISUALDSPVERSION__>>16 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__VISUALDSPVERSION__>>8 & 0xFF) + +/* Analog VisualDSP++ < 4.5.6 */ +#elif defined(__ADSPBLACKFIN__) || defined(__ADSPTS__) || defined(__ADSP21000__) +# define COMPILER_ID "ADSP" + +/* IAR Systems compiler for embedded systems. + http://www.iar.com */ +#elif defined(__IAR_SYSTEMS_ICC__ ) || defined(__IAR_SYSTEMS_ICC) +# define COMPILER_ID "IAR" + +/* sdcc, the small devices C compiler for embedded systems, + http://sdcc.sourceforge.net */ +#elif defined(SDCC) +# define COMPILER_ID "SDCC" + /* SDCC = VRP */ +# define COMPILER_VERSION_MAJOR DEC(SDCC/100) +# define COMPILER_VERSION_MINOR DEC(SDCC/10 % 10) +# define COMPILER_VERSION_PATCH DEC(SDCC % 10) + +#elif defined(_SGI_COMPILER_VERSION) || defined(_COMPILER_VERSION) +# define COMPILER_ID "MIPSpro" +# if defined(_SGI_COMPILER_VERSION) + /* _SGI_COMPILER_VERSION = VRP */ +# define COMPILER_VERSION_MAJOR DEC(_SGI_COMPILER_VERSION/100) +# define COMPILER_VERSION_MINOR DEC(_SGI_COMPILER_VERSION/10 % 10) +# define COMPILER_VERSION_PATCH DEC(_SGI_COMPILER_VERSION % 10) +# else + /* _COMPILER_VERSION = VRP */ +# define COMPILER_VERSION_MAJOR DEC(_COMPILER_VERSION/100) +# define COMPILER_VERSION_MINOR DEC(_COMPILER_VERSION/10 % 10) +# define COMPILER_VERSION_PATCH DEC(_COMPILER_VERSION % 10) +# endif + +/* This compiler is either not known or is too old to define an + identification macro. Try to identify the platform and guess that + it is the native compiler. */ +#elif defined(__sgi) +# define COMPILER_ID "MIPSpro" + +#elif defined(__hpux) || defined(__hpua) +# define COMPILER_ID "HP" + +#else /* unknown compiler */ +# define COMPILER_ID "" + +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_compiler = "INFO" ":" "compiler[" COMPILER_ID "]"; + +/* Identify known platforms by name. */ +#if defined(__linux) || defined(__linux__) || defined(linux) +# define PLATFORM_ID "Linux" + +#elif defined(__CYGWIN__) +# define PLATFORM_ID "Cygwin" + +#elif defined(__MINGW32__) +# define PLATFORM_ID "MinGW" + +#elif defined(__APPLE__) +# define PLATFORM_ID "Darwin" + +#elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32) +# define PLATFORM_ID "Windows" + +#elif defined(__FreeBSD__) || defined(__FreeBSD) +# define PLATFORM_ID "FreeBSD" + +#elif defined(__NetBSD__) || defined(__NetBSD) +# define PLATFORM_ID "NetBSD" + +#elif defined(__OpenBSD__) || defined(__OPENBSD) +# define PLATFORM_ID "OpenBSD" + +#elif defined(__sun) || defined(sun) +# define PLATFORM_ID "SunOS" + +#elif defined(_AIX) || defined(__AIX) || defined(__AIX__) || defined(__aix) || defined(__aix__) +# define PLATFORM_ID "AIX" + +#elif defined(__sgi) || defined(__sgi__) || defined(_SGI) +# define PLATFORM_ID "IRIX" + +#elif defined(__hpux) || defined(__hpux__) +# define PLATFORM_ID "HP-UX" + +#elif defined(__HAIKU__) +# define PLATFORM_ID "Haiku" + +#elif defined(__BeOS) || defined(__BEOS__) || defined(_BEOS) +# define PLATFORM_ID "BeOS" + +#elif defined(__QNX__) || defined(__QNXNTO__) +# define PLATFORM_ID "QNX" + +#elif defined(__tru64) || defined(_tru64) || defined(__TRU64__) +# define PLATFORM_ID "Tru64" + +#elif defined(__riscos) || defined(__riscos__) +# define PLATFORM_ID "RISCos" + +#elif defined(__sinix) || defined(__sinix__) || defined(__SINIX__) +# define PLATFORM_ID "SINIX" + +#elif defined(__UNIX_SV__) +# define PLATFORM_ID "UNIX_SV" + +#elif defined(__bsdos__) +# define PLATFORM_ID "BSDOS" + +#elif defined(_MPRAS) || defined(MPRAS) +# define PLATFORM_ID "MP-RAS" + +#elif defined(__osf) || defined(__osf__) +# define PLATFORM_ID "OSF1" + +#elif defined(_SCO_SV) || defined(SCO_SV) || defined(sco_sv) +# define PLATFORM_ID "SCO_SV" + +#elif defined(__ultrix) || defined(__ultrix__) || defined(_ULTRIX) +# define PLATFORM_ID "ULTRIX" + +#elif defined(__XENIX__) || defined(_XENIX) || defined(XENIX) +# define PLATFORM_ID "Xenix" + +#else /* unknown platform */ +# define PLATFORM_ID "" + +#endif + +/* For windows compilers MSVC and Intel we can determine + the architecture of the compiler being used. This is because + the compilers do not have flags that can change the architecture, + but rather depend on which compiler is being used +*/ +#if defined(_WIN32) && defined(_MSC_VER) +# if defined(_M_IA64) +# define ARCHITECTURE_ID "IA64" + +# elif defined(_M_X64) || defined(_M_AMD64) +# define ARCHITECTURE_ID "x64" + +# elif defined(_M_IX86) +# define ARCHITECTURE_ID "X86" + +# elif defined(_M_ARM) +# define ARCHITECTURE_ID "ARM" + +# elif defined(_M_MIPS) +# define ARCHITECTURE_ID "MIPS" + +# elif defined(_M_SH) +# define ARCHITECTURE_ID "SHx" + +# else /* unknown architecture */ +# define ARCHITECTURE_ID "" +# endif + +#else +# define ARCHITECTURE_ID "" +#endif + +/* Convert integer to decimal digit literals. */ +#define DEC(n) \ + ('0' + (((n) / 10000000)%10)), \ + ('0' + (((n) / 1000000)%10)), \ + ('0' + (((n) / 100000)%10)), \ + ('0' + (((n) / 10000)%10)), \ + ('0' + (((n) / 1000)%10)), \ + ('0' + (((n) / 100)%10)), \ + ('0' + (((n) / 10)%10)), \ + ('0' + ((n) % 10)) + +/* Convert integer to hex digit literals. */ +#define HEX(n) \ + ('0' + ((n)>>28 & 0xF)), \ + ('0' + ((n)>>24 & 0xF)), \ + ('0' + ((n)>>20 & 0xF)), \ + ('0' + ((n)>>16 & 0xF)), \ + ('0' + ((n)>>12 & 0xF)), \ + ('0' + ((n)>>8 & 0xF)), \ + ('0' + ((n)>>4 & 0xF)), \ + ('0' + ((n) & 0xF)) + +/* Construct a string literal encoding the version number components. */ +#ifdef COMPILER_VERSION_MAJOR +char const info_version[] = { + 'I', 'N', 'F', 'O', ':', + 'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','[', + COMPILER_VERSION_MAJOR, +# ifdef COMPILER_VERSION_MINOR + '.', COMPILER_VERSION_MINOR, +# ifdef COMPILER_VERSION_PATCH + '.', COMPILER_VERSION_PATCH, +# ifdef COMPILER_VERSION_TWEAK + '.', COMPILER_VERSION_TWEAK, +# endif +# endif +# endif + ']','\0'}; +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_platform = "INFO" ":" "platform[" PLATFORM_ID "]"; +char const* info_arch = "INFO" ":" "arch[" ARCHITECTURE_ID "]"; + + + +/*--------------------------------------------------------------------------*/ + +#ifdef ID_VOID_MAIN +void main() {} +#else +int main(int argc, char* argv[]) +{ + int require = 0; + require += info_compiler[argc]; + require += info_platform[argc]; + require += info_arch[argc]; +#ifdef COMPILER_VERSION_MAJOR + require += info_version[argc]; +#endif + (void)argv; + return require; +} +#endif diff --git a/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CompilerIdC/a.out b/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CompilerIdC/a.out new file mode 100755 index 00000000..49a5ca2e Binary files /dev/null and b/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CompilerIdC/a.out differ diff --git a/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CompilerIdCXX/CMakeCXXCompilerId.cpp b/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CompilerIdCXX/CMakeCXXCompilerId.cpp new file mode 100644 index 00000000..e8220b26 --- /dev/null +++ b/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CompilerIdCXX/CMakeCXXCompilerId.cpp @@ -0,0 +1,377 @@ +/* This source file must have a .cpp extension so that all C++ compilers + recognize the extension without flags. Borland does not know .cxx for + example. */ +#ifndef __cplusplus +# error "A C compiler has been selected for C++." +#endif + +/* Version number components: V=Version, R=Revision, P=Patch + Version date components: YYYY=Year, MM=Month, DD=Day */ + +#if defined(__COMO__) +# define COMPILER_ID "Comeau" + /* __COMO_VERSION__ = VRR */ +# define COMPILER_VERSION_MAJOR DEC(__COMO_VERSION__ / 100) +# define COMPILER_VERSION_MINOR DEC(__COMO_VERSION__ % 100) + +#elif defined(__INTEL_COMPILER) || defined(__ICC) +# define COMPILER_ID "Intel" + /* __INTEL_COMPILER = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER/100) +# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER % 10) +# if defined(__INTEL_COMPILER_BUILD_DATE) + /* __INTEL_COMPILER_BUILD_DATE = YYYYMMDD */ +# define COMPILER_VERSION_TWEAK DEC(__INTEL_COMPILER_BUILD_DATE) +# endif + +#elif defined(__PATHCC__) +# define COMPILER_ID "PathScale" +# define COMPILER_VERSION_MAJOR DEC(__PATHCC__) +# define COMPILER_VERSION_MINOR DEC(__PATHCC_MINOR__) +# if defined(__PATHCC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__PATHCC_PATCHLEVEL__) +# endif + +#elif defined(__clang__) +# define COMPILER_ID "Clang" +# define COMPILER_VERSION_MAJOR DEC(__clang_major__) +# define COMPILER_VERSION_MINOR DEC(__clang_minor__) +# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__) + +#elif defined(__BORLANDC__) && defined(__CODEGEARC_VERSION__) +# define COMPILER_ID "Embarcadero" +# define COMPILER_VERSION_MAJOR HEX(__CODEGEARC_VERSION__>>24 & 0x00FF) +# define COMPILER_VERSION_MINOR HEX(__CODEGEARC_VERSION__>>16 & 0x00FF) +# define COMPILER_VERSION_PATCH HEX(__CODEGEARC_VERSION__ & 0xFFFF) + +#elif defined(__BORLANDC__) +# define COMPILER_ID "Borland" + /* __BORLANDC__ = 0xVRR */ +# define COMPILER_VERSION_MAJOR HEX(__BORLANDC__>>8) +# define COMPILER_VERSION_MINOR HEX(__BORLANDC__ & 0xFF) + +#elif defined(__WATCOMC__) +# define COMPILER_ID "Watcom" + /* __WATCOMC__ = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(__WATCOMC__ / 100) +# define COMPILER_VERSION_MINOR DEC(__WATCOMC__ % 100) + +#elif defined(__SUNPRO_CC) +# define COMPILER_ID "SunPro" +# if __SUNPRO_CC >= 0x5100 + /* __SUNPRO_CC = 0xVRRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_CC>>12) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_CC>>4 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_CC & 0xF) +# else + /* __SUNPRO_CC = 0xVRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_CC>>8) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_CC>>4 & 0xF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_CC & 0xF) +# endif + +#elif defined(__HP_aCC) +# define COMPILER_ID "HP" + /* __HP_aCC = VVRRPP */ +# define COMPILER_VERSION_MAJOR DEC(__HP_aCC/10000) +# define COMPILER_VERSION_MINOR DEC(__HP_aCC/100 % 100) +# define COMPILER_VERSION_PATCH DEC(__HP_aCC % 100) + +#elif defined(__DECCXX) +# define COMPILER_ID "Compaq" + /* __DECCXX_VER = VVRRTPPPP */ +# define COMPILER_VERSION_MAJOR DEC(__DECCXX_VER/10000000) +# define COMPILER_VERSION_MINOR DEC(__DECCXX_VER/100000 % 100) +# define COMPILER_VERSION_PATCH DEC(__DECCXX_VER % 10000) + +#elif defined(__IBMCPP__) +# if defined(__COMPILER_VER__) +# define COMPILER_ID "zOS" +# else +# if __IBMCPP__ >= 800 +# define COMPILER_ID "XL" +# else +# define COMPILER_ID "VisualAge" +# endif + /* __IBMCPP__ = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__IBMCPP__/100) +# define COMPILER_VERSION_MINOR DEC(__IBMCPP__/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__IBMCPP__ % 10) +# endif + +#elif defined(__PGI) +# define COMPILER_ID "PGI" +# define COMPILER_VERSION_MAJOR DEC(__PGIC__) +# define COMPILER_VERSION_MINOR DEC(__PGIC_MINOR__) +# if defined(__PGIC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__PGIC_PATCHLEVEL__) +# endif + +#elif defined(_CRAYC) +# define COMPILER_ID "Cray" +# define COMPILER_VERSION_MAJOR DEC(_RELEASE) +# define COMPILER_VERSION_MINOR DEC(_RELEASE_MINOR) + +#elif defined(__TI_COMPILER_VERSION__) +# define COMPILER_ID "TI" + /* __TI_COMPILER_VERSION__ = VVVRRRPPP */ +# define COMPILER_VERSION_MAJOR DEC(__TI_COMPILER_VERSION__/1000000) +# define COMPILER_VERSION_MINOR DEC(__TI_COMPILER_VERSION__/1000 % 1000) +# define COMPILER_VERSION_PATCH DEC(__TI_COMPILER_VERSION__ % 1000) + +#elif defined(__SCO_VERSION__) +# define COMPILER_ID "SCO" + +#elif defined(__GNUC__) +# define COMPILER_ID "GNU" +# define COMPILER_VERSION_MAJOR DEC(__GNUC__) +# define COMPILER_VERSION_MINOR DEC(__GNUC_MINOR__) +# if defined(__GNUC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__) +# endif + +#elif defined(_MSC_VER) +# define COMPILER_ID "MSVC" + /* _MSC_VER = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(_MSC_VER / 100) +# define COMPILER_VERSION_MINOR DEC(_MSC_VER % 100) +# if defined(_MSC_FULL_VER) +# if _MSC_VER >= 1400 + /* _MSC_FULL_VER = VVRRPPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 100000) +# else + /* _MSC_FULL_VER = VVRRPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 10000) +# endif +# endif +# if defined(_MSC_BUILD) +# define COMPILER_VERSION_TWEAK DEC(_MSC_BUILD) +# endif + +/* Analog VisualDSP++ >= 4.5.6 */ +#elif defined(__VISUALDSPVERSION__) +# define COMPILER_ID "ADSP" + /* __VISUALDSPVERSION__ = 0xVVRRPP00 */ +# define COMPILER_VERSION_MAJOR HEX(__VISUALDSPVERSION__>>24) +# define COMPILER_VERSION_MINOR HEX(__VISUALDSPVERSION__>>16 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__VISUALDSPVERSION__>>8 & 0xFF) + +/* Analog VisualDSP++ < 4.5.6 */ +#elif defined(__ADSPBLACKFIN__) || defined(__ADSPTS__) || defined(__ADSP21000__) +# define COMPILER_ID "ADSP" + +/* IAR Systems compiler for embedded systems. + http://www.iar.com */ +#elif defined(__IAR_SYSTEMS_ICC__ ) || defined(__IAR_SYSTEMS_ICC) +# define COMPILER_ID "IAR" + +#elif defined(_SGI_COMPILER_VERSION) || defined(_COMPILER_VERSION) +# define COMPILER_ID "MIPSpro" +# if defined(_SGI_COMPILER_VERSION) + /* _SGI_COMPILER_VERSION = VRP */ +# define COMPILER_VERSION_MAJOR DEC(_SGI_COMPILER_VERSION/100) +# define COMPILER_VERSION_MINOR DEC(_SGI_COMPILER_VERSION/10 % 10) +# define COMPILER_VERSION_PATCH DEC(_SGI_COMPILER_VERSION % 10) +# else + /* _COMPILER_VERSION = VRP */ +# define COMPILER_VERSION_MAJOR DEC(_COMPILER_VERSION/100) +# define COMPILER_VERSION_MINOR DEC(_COMPILER_VERSION/10 % 10) +# define COMPILER_VERSION_PATCH DEC(_COMPILER_VERSION % 10) +# endif + +/* This compiler is either not known or is too old to define an + identification macro. Try to identify the platform and guess that + it is the native compiler. */ +#elif defined(__sgi) +# define COMPILER_ID "MIPSpro" + +#elif defined(__hpux) || defined(__hpua) +# define COMPILER_ID "HP" + +#else /* unknown compiler */ +# define COMPILER_ID "" + +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_compiler = "INFO" ":" "compiler[" COMPILER_ID "]"; + +/* Identify known platforms by name. */ +#if defined(__linux) || defined(__linux__) || defined(linux) +# define PLATFORM_ID "Linux" + +#elif defined(__CYGWIN__) +# define PLATFORM_ID "Cygwin" + +#elif defined(__MINGW32__) +# define PLATFORM_ID "MinGW" + +#elif defined(__APPLE__) +# define PLATFORM_ID "Darwin" + +#elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32) +# define PLATFORM_ID "Windows" + +#elif defined(__FreeBSD__) || defined(__FreeBSD) +# define PLATFORM_ID "FreeBSD" + +#elif defined(__NetBSD__) || defined(__NetBSD) +# define PLATFORM_ID "NetBSD" + +#elif defined(__OpenBSD__) || defined(__OPENBSD) +# define PLATFORM_ID "OpenBSD" + +#elif defined(__sun) || defined(sun) +# define PLATFORM_ID "SunOS" + +#elif defined(_AIX) || defined(__AIX) || defined(__AIX__) || defined(__aix) || defined(__aix__) +# define PLATFORM_ID "AIX" + +#elif defined(__sgi) || defined(__sgi__) || defined(_SGI) +# define PLATFORM_ID "IRIX" + +#elif defined(__hpux) || defined(__hpux__) +# define PLATFORM_ID "HP-UX" + +#elif defined(__HAIKU__) +# define PLATFORM_ID "Haiku" + +#elif defined(__BeOS) || defined(__BEOS__) || defined(_BEOS) +# define PLATFORM_ID "BeOS" + +#elif defined(__QNX__) || defined(__QNXNTO__) +# define PLATFORM_ID "QNX" + +#elif defined(__tru64) || defined(_tru64) || defined(__TRU64__) +# define PLATFORM_ID "Tru64" + +#elif defined(__riscos) || defined(__riscos__) +# define PLATFORM_ID "RISCos" + +#elif defined(__sinix) || defined(__sinix__) || defined(__SINIX__) +# define PLATFORM_ID "SINIX" + +#elif defined(__UNIX_SV__) +# define PLATFORM_ID "UNIX_SV" + +#elif defined(__bsdos__) +# define PLATFORM_ID "BSDOS" + +#elif defined(_MPRAS) || defined(MPRAS) +# define PLATFORM_ID "MP-RAS" + +#elif defined(__osf) || defined(__osf__) +# define PLATFORM_ID "OSF1" + +#elif defined(_SCO_SV) || defined(SCO_SV) || defined(sco_sv) +# define PLATFORM_ID "SCO_SV" + +#elif defined(__ultrix) || defined(__ultrix__) || defined(_ULTRIX) +# define PLATFORM_ID "ULTRIX" + +#elif defined(__XENIX__) || defined(_XENIX) || defined(XENIX) +# define PLATFORM_ID "Xenix" + +#else /* unknown platform */ +# define PLATFORM_ID "" + +#endif + +/* For windows compilers MSVC and Intel we can determine + the architecture of the compiler being used. This is because + the compilers do not have flags that can change the architecture, + but rather depend on which compiler is being used +*/ +#if defined(_WIN32) && defined(_MSC_VER) +# if defined(_M_IA64) +# define ARCHITECTURE_ID "IA64" + +# elif defined(_M_X64) || defined(_M_AMD64) +# define ARCHITECTURE_ID "x64" + +# elif defined(_M_IX86) +# define ARCHITECTURE_ID "X86" + +# elif defined(_M_ARM) +# define ARCHITECTURE_ID "ARM" + +# elif defined(_M_MIPS) +# define ARCHITECTURE_ID "MIPS" + +# elif defined(_M_SH) +# define ARCHITECTURE_ID "SHx" + +# else /* unknown architecture */ +# define ARCHITECTURE_ID "" +# endif + +#else +# define ARCHITECTURE_ID "" +#endif + +/* Convert integer to decimal digit literals. */ +#define DEC(n) \ + ('0' + (((n) / 10000000)%10)), \ + ('0' + (((n) / 1000000)%10)), \ + ('0' + (((n) / 100000)%10)), \ + ('0' + (((n) / 10000)%10)), \ + ('0' + (((n) / 1000)%10)), \ + ('0' + (((n) / 100)%10)), \ + ('0' + (((n) / 10)%10)), \ + ('0' + ((n) % 10)) + +/* Convert integer to hex digit literals. */ +#define HEX(n) \ + ('0' + ((n)>>28 & 0xF)), \ + ('0' + ((n)>>24 & 0xF)), \ + ('0' + ((n)>>20 & 0xF)), \ + ('0' + ((n)>>16 & 0xF)), \ + ('0' + ((n)>>12 & 0xF)), \ + ('0' + ((n)>>8 & 0xF)), \ + ('0' + ((n)>>4 & 0xF)), \ + ('0' + ((n) & 0xF)) + +/* Construct a string literal encoding the version number components. */ +#ifdef COMPILER_VERSION_MAJOR +char const info_version[] = { + 'I', 'N', 'F', 'O', ':', + 'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','[', + COMPILER_VERSION_MAJOR, +# ifdef COMPILER_VERSION_MINOR + '.', COMPILER_VERSION_MINOR, +# ifdef COMPILER_VERSION_PATCH + '.', COMPILER_VERSION_PATCH, +# ifdef COMPILER_VERSION_TWEAK + '.', COMPILER_VERSION_TWEAK, +# endif +# endif +# endif + ']','\0'}; +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_platform = "INFO" ":" "platform[" PLATFORM_ID "]"; +char const* info_arch = "INFO" ":" "arch[" ARCHITECTURE_ID "]"; + + + +/*--------------------------------------------------------------------------*/ + +int main(int argc, char* argv[]) +{ + int require = 0; + require += info_compiler[argc]; + require += info_platform[argc]; +#ifdef COMPILER_VERSION_MAJOR + require += info_version[argc]; +#endif + (void)argv; + return require; +} diff --git a/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CompilerIdCXX/a.out b/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CompilerIdCXX/a.out new file mode 100755 index 00000000..96c16077 Binary files /dev/null and b/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CompilerIdCXX/a.out differ diff --git a/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeDirectoryInformation.cmake b/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeDirectoryInformation.cmake new file mode 100644 index 00000000..1e619e8c --- /dev/null +++ b/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeDirectoryInformation.cmake @@ -0,0 +1,16 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Relative path conversion top directories. +SET(CMAKE_RELATIVE_PATH_TOP_SOURCE "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow") +SET(CMAKE_RELATIVE_PATH_TOP_BINARY "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build") + +# Force unix paths in dependencies. +SET(CMAKE_FORCE_UNIX_PATHS 1) + + +# The C and CXX include file regular expressions for this directory. +SET(CMAKE_C_INCLUDE_REGEX_SCAN "^.*$") +SET(CMAKE_C_INCLUDE_REGEX_COMPLAIN "^$") +SET(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN}) +SET(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN}) diff --git a/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeOutput.log b/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeOutput.log new file mode 100644 index 00000000..feab36d7 --- /dev/null +++ b/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeOutput.log @@ -0,0 +1,263 @@ +The system is: Linux - 4.4.0-94-generic - x86_64 +Compiling the C compiler identification source file "CMakeCCompilerId.c" succeeded. +Compiler: /usr/bin/cc +Build flags: +Id flags: + +The output was: +0 + + +Compilation of the C compiler identification source "CMakeCCompilerId.c" produced "a.out" + +The C compiler identification is GNU, found in "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CompilerIdC/a.out" + +Compiling the CXX compiler identification source file "CMakeCXXCompilerId.cpp" succeeded. +Compiler: /usr/bin/c++ +Build flags: +Id flags: + +The output was: +0 + + +Compilation of the CXX compiler identification source "CMakeCXXCompilerId.cpp" produced "a.out" + +The CXX compiler identification is GNU, found in "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/2.8.12.2/CompilerIdCXX/a.out" + +Determining if the C compiler works passed with the following output: +Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeTmp + +Run Build Command:/usr/bin/make "cmTryCompileExec4072475654/fast" +/usr/bin/make -f CMakeFiles/cmTryCompileExec4072475654.dir/build.make CMakeFiles/cmTryCompileExec4072475654.dir/build +make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeTmp' +/usr/bin/cmake -E cmake_progress_report /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeTmp/CMakeFiles 1 +Building C object CMakeFiles/cmTryCompileExec4072475654.dir/testCCompiler.c.o +/usr/bin/cc -o CMakeFiles/cmTryCompileExec4072475654.dir/testCCompiler.c.o -c /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeTmp/testCCompiler.c +Linking C executable cmTryCompileExec4072475654 +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec4072475654.dir/link.txt --verbose=1 +/usr/bin/cc CMakeFiles/cmTryCompileExec4072475654.dir/testCCompiler.c.o -o cmTryCompileExec4072475654 -rdynamic +make[1]: Leaving directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeTmp' + + +Detecting C compiler ABI info compiled with the following output: +Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeTmp + +Run Build Command:/usr/bin/make "cmTryCompileExec4258416926/fast" +/usr/bin/make -f CMakeFiles/cmTryCompileExec4258416926.dir/build.make CMakeFiles/cmTryCompileExec4258416926.dir/build +make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeTmp' +/usr/bin/cmake -E cmake_progress_report /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeTmp/CMakeFiles 1 +Building C object CMakeFiles/cmTryCompileExec4258416926.dir/CMakeCCompilerABI.c.o +/usr/bin/cc -o CMakeFiles/cmTryCompileExec4258416926.dir/CMakeCCompilerABI.c.o -c /usr/share/cmake-2.8/Modules/CMakeCCompilerABI.c +Linking C executable cmTryCompileExec4258416926 +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec4258416926.dir/link.txt --verbose=1 +/usr/bin/cc -v CMakeFiles/cmTryCompileExec4258416926.dir/CMakeCCompilerABI.c.o -o cmTryCompileExec4258416926 -rdynamic +Using built-in specs. +COLLECT_GCC=/usr/bin/cc +COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/4.8/lto-wrapper +Target: x86_64-linux-gnu +Configured with: ../src/configure -v --with-pkgversion='Ubuntu 4.8.4-2ubuntu1~14.04.3' --with-bugurl=file:///usr/share/doc/gcc-4.8/README.Bugs --enable-languages=c,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-4.8 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --with-gxx-include-dir=/usr/include/c++/4.8 --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --enable-gnu-unique-object --disable-libmudflap --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-4.8-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu +Thread model: posix +gcc version 4.8.4 (Ubuntu 4.8.4-2ubuntu1~14.04.3) +COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/ +LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../:/lib/:/usr/lib/ +COLLECT_GCC_OPTIONS='-v' '-o' 'cmTryCompileExec4258416926' '-rdynamic' '-mtune=generic' '-march=x86-64' + /usr/lib/gcc/x86_64-linux-gnu/4.8/collect2 --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTryCompileExec4258416926 /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/4.8 -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../.. CMakeFiles/cmTryCompileExec4258416926.dir/CMakeCCompilerABI.c.o -lgcc --as-needed -lgcc_s --no-as-needed -lc -lgcc --as-needed -lgcc_s --no-as-needed /usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o +make[1]: Leaving directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeTmp' + + +Parsed C implicit link information from above output: + link line regex: [^( *|.*[/\])(ld|([^/\]+-)?ld|collect2)[^/\]*( |$)] + ignore line: [Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeTmp] + ignore line: [] + ignore line: [Run Build Command:/usr/bin/make "cmTryCompileExec4258416926/fast"] + ignore line: [/usr/bin/make -f CMakeFiles/cmTryCompileExec4258416926.dir/build.make CMakeFiles/cmTryCompileExec4258416926.dir/build] + ignore line: [make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeTmp'] + ignore line: [/usr/bin/cmake -E cmake_progress_report /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeTmp/CMakeFiles 1] + ignore line: [Building C object CMakeFiles/cmTryCompileExec4258416926.dir/CMakeCCompilerABI.c.o] + ignore line: [/usr/bin/cc -o CMakeFiles/cmTryCompileExec4258416926.dir/CMakeCCompilerABI.c.o -c /usr/share/cmake-2.8/Modules/CMakeCCompilerABI.c] + ignore line: [Linking C executable cmTryCompileExec4258416926] + ignore line: [/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec4258416926.dir/link.txt --verbose=1] + ignore line: [/usr/bin/cc -v CMakeFiles/cmTryCompileExec4258416926.dir/CMakeCCompilerABI.c.o -o cmTryCompileExec4258416926 -rdynamic ] + ignore line: [Using built-in specs.] + ignore line: [COLLECT_GCC=/usr/bin/cc] + ignore line: [COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/4.8/lto-wrapper] + ignore line: [Target: x86_64-linux-gnu] + ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 4.8.4-2ubuntu1~14.04.3' --with-bugurl=file:///usr/share/doc/gcc-4.8/README.Bugs --enable-languages=c,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-4.8 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --with-gxx-include-dir=/usr/include/c++/4.8 --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --enable-gnu-unique-object --disable-libmudflap --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-4.8-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu] + ignore line: [Thread model: posix] + ignore line: [gcc version 4.8.4 (Ubuntu 4.8.4-2ubuntu1~14.04.3) ] + ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/] + ignore line: [LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../:/lib/:/usr/lib/] + ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'cmTryCompileExec4258416926' '-rdynamic' '-mtune=generic' '-march=x86-64'] + link line: [ /usr/lib/gcc/x86_64-linux-gnu/4.8/collect2 --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTryCompileExec4258416926 /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/4.8 -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../.. CMakeFiles/cmTryCompileExec4258416926.dir/CMakeCCompilerABI.c.o -lgcc --as-needed -lgcc_s --no-as-needed -lc -lgcc --as-needed -lgcc_s --no-as-needed /usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o] + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/collect2] ==> ignore + arg [--sysroot=/] ==> ignore + arg [--build-id] ==> ignore + arg [--eh-frame-hdr] ==> ignore + arg [-m] ==> ignore + arg [elf_x86_64] ==> ignore + arg [--hash-style=gnu] ==> ignore + arg [--as-needed] ==> ignore + arg [-export-dynamic] ==> ignore + arg [-dynamic-linker] ==> ignore + arg [/lib64/ld-linux-x86-64.so.2] ==> ignore + arg [-zrelro] ==> ignore + arg [-o] ==> ignore + arg [cmTryCompileExec4258416926] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o] ==> ignore + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] + arg [-L/lib/x86_64-linux-gnu] ==> dir [/lib/x86_64-linux-gnu] + arg [-L/lib/../lib] ==> dir [/lib/../lib] + arg [-L/usr/lib/x86_64-linux-gnu] ==> dir [/usr/lib/x86_64-linux-gnu] + arg [-L/usr/lib/../lib] ==> dir [/usr/lib/../lib] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] + arg [CMakeFiles/cmTryCompileExec4258416926.dir/CMakeCCompilerABI.c.o] ==> ignore + arg [-lgcc] ==> lib [gcc] + arg [--as-needed] ==> ignore + arg [-lgcc_s] ==> lib [gcc_s] + arg [--no-as-needed] ==> ignore + arg [-lc] ==> lib [c] + arg [-lgcc] ==> lib [gcc] + arg [--as-needed] ==> ignore + arg [-lgcc_s] ==> lib [gcc_s] + arg [--no-as-needed] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o] ==> ignore + remove lib [gcc] + remove lib [gcc_s] + remove lib [gcc] + remove lib [gcc_s] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8] ==> [/usr/lib/gcc/x86_64-linux-gnu/4.8] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] ==> [/usr/lib] + collapse library dir [/lib/x86_64-linux-gnu] ==> [/lib/x86_64-linux-gnu] + collapse library dir [/lib/../lib] ==> [/lib] + collapse library dir [/usr/lib/x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/../lib] ==> [/usr/lib] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] ==> [/usr/lib] + implicit libs: [c] + implicit dirs: [/usr/lib/gcc/x86_64-linux-gnu/4.8;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib] + implicit fwks: [] + + +Determining if the CXX compiler works passed with the following output: +Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeTmp + +Run Build Command:/usr/bin/make "cmTryCompileExec3642391334/fast" +/usr/bin/make -f CMakeFiles/cmTryCompileExec3642391334.dir/build.make CMakeFiles/cmTryCompileExec3642391334.dir/build +make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeTmp' +/usr/bin/cmake -E cmake_progress_report /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeTmp/CMakeFiles 1 +Building CXX object CMakeFiles/cmTryCompileExec3642391334.dir/testCXXCompiler.cxx.o +/usr/bin/c++ -o CMakeFiles/cmTryCompileExec3642391334.dir/testCXXCompiler.cxx.o -c /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeTmp/testCXXCompiler.cxx +Linking CXX executable cmTryCompileExec3642391334 +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec3642391334.dir/link.txt --verbose=1 +/usr/bin/c++ CMakeFiles/cmTryCompileExec3642391334.dir/testCXXCompiler.cxx.o -o cmTryCompileExec3642391334 -rdynamic +make[1]: Leaving directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeTmp' + + +Detecting CXX compiler ABI info compiled with the following output: +Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeTmp + +Run Build Command:/usr/bin/make "cmTryCompileExec1351686098/fast" +/usr/bin/make -f CMakeFiles/cmTryCompileExec1351686098.dir/build.make CMakeFiles/cmTryCompileExec1351686098.dir/build +make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeTmp' +/usr/bin/cmake -E cmake_progress_report /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeTmp/CMakeFiles 1 +Building CXX object CMakeFiles/cmTryCompileExec1351686098.dir/CMakeCXXCompilerABI.cpp.o +/usr/bin/c++ -o CMakeFiles/cmTryCompileExec1351686098.dir/CMakeCXXCompilerABI.cpp.o -c /usr/share/cmake-2.8/Modules/CMakeCXXCompilerABI.cpp +Linking CXX executable cmTryCompileExec1351686098 +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec1351686098.dir/link.txt --verbose=1 +/usr/bin/c++ -v CMakeFiles/cmTryCompileExec1351686098.dir/CMakeCXXCompilerABI.cpp.o -o cmTryCompileExec1351686098 -rdynamic +Using built-in specs. +COLLECT_GCC=/usr/bin/c++ +COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/4.8/lto-wrapper +Target: x86_64-linux-gnu +Configured with: ../src/configure -v --with-pkgversion='Ubuntu 4.8.4-2ubuntu1~14.04.3' --with-bugurl=file:///usr/share/doc/gcc-4.8/README.Bugs --enable-languages=c,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-4.8 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --with-gxx-include-dir=/usr/include/c++/4.8 --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --enable-gnu-unique-object --disable-libmudflap --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-4.8-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu +Thread model: posix +gcc version 4.8.4 (Ubuntu 4.8.4-2ubuntu1~14.04.3) +COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/ +LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../:/lib/:/usr/lib/ +COLLECT_GCC_OPTIONS='-v' '-o' 'cmTryCompileExec1351686098' '-rdynamic' '-shared-libgcc' '-mtune=generic' '-march=x86-64' + /usr/lib/gcc/x86_64-linux-gnu/4.8/collect2 --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTryCompileExec1351686098 /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/4.8 -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../.. CMakeFiles/cmTryCompileExec1351686098.dir/CMakeCXXCompilerABI.cpp.o -lstdc++ -lm -lgcc_s -lgcc -lc -lgcc_s -lgcc /usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o +make[1]: Leaving directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeTmp' + + +Parsed CXX implicit link information from above output: + link line regex: [^( *|.*[/\])(ld|([^/\]+-)?ld|collect2)[^/\]*( |$)] + ignore line: [Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeTmp] + ignore line: [] + ignore line: [Run Build Command:/usr/bin/make "cmTryCompileExec1351686098/fast"] + ignore line: [/usr/bin/make -f CMakeFiles/cmTryCompileExec1351686098.dir/build.make CMakeFiles/cmTryCompileExec1351686098.dir/build] + ignore line: [make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeTmp'] + ignore line: [/usr/bin/cmake -E cmake_progress_report /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/CMakeTmp/CMakeFiles 1] + ignore line: [Building CXX object CMakeFiles/cmTryCompileExec1351686098.dir/CMakeCXXCompilerABI.cpp.o] + ignore line: [/usr/bin/c++ -o CMakeFiles/cmTryCompileExec1351686098.dir/CMakeCXXCompilerABI.cpp.o -c /usr/share/cmake-2.8/Modules/CMakeCXXCompilerABI.cpp] + ignore line: [Linking CXX executable cmTryCompileExec1351686098] + ignore line: [/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec1351686098.dir/link.txt --verbose=1] + ignore line: [/usr/bin/c++ -v CMakeFiles/cmTryCompileExec1351686098.dir/CMakeCXXCompilerABI.cpp.o -o cmTryCompileExec1351686098 -rdynamic ] + ignore line: [Using built-in specs.] + ignore line: [COLLECT_GCC=/usr/bin/c++] + ignore line: [COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/4.8/lto-wrapper] + ignore line: [Target: x86_64-linux-gnu] + ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 4.8.4-2ubuntu1~14.04.3' --with-bugurl=file:///usr/share/doc/gcc-4.8/README.Bugs --enable-languages=c,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-4.8 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --with-gxx-include-dir=/usr/include/c++/4.8 --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --enable-gnu-unique-object --disable-libmudflap --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-4.8-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu] + ignore line: [Thread model: posix] + ignore line: [gcc version 4.8.4 (Ubuntu 4.8.4-2ubuntu1~14.04.3) ] + ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/] + ignore line: [LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../:/lib/:/usr/lib/] + ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'cmTryCompileExec1351686098' '-rdynamic' '-shared-libgcc' '-mtune=generic' '-march=x86-64'] + link line: [ /usr/lib/gcc/x86_64-linux-gnu/4.8/collect2 --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTryCompileExec1351686098 /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/4.8 -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../.. CMakeFiles/cmTryCompileExec1351686098.dir/CMakeCXXCompilerABI.cpp.o -lstdc++ -lm -lgcc_s -lgcc -lc -lgcc_s -lgcc /usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o] + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/collect2] ==> ignore + arg [--sysroot=/] ==> ignore + arg [--build-id] ==> ignore + arg [--eh-frame-hdr] ==> ignore + arg [-m] ==> ignore + arg [elf_x86_64] ==> ignore + arg [--hash-style=gnu] ==> ignore + arg [--as-needed] ==> ignore + arg [-export-dynamic] ==> ignore + arg [-dynamic-linker] ==> ignore + arg [/lib64/ld-linux-x86-64.so.2] ==> ignore + arg [-zrelro] ==> ignore + arg [-o] ==> ignore + arg [cmTryCompileExec1351686098] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o] ==> ignore + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] + arg [-L/lib/x86_64-linux-gnu] ==> dir [/lib/x86_64-linux-gnu] + arg [-L/lib/../lib] ==> dir [/lib/../lib] + arg [-L/usr/lib/x86_64-linux-gnu] ==> dir [/usr/lib/x86_64-linux-gnu] + arg [-L/usr/lib/../lib] ==> dir [/usr/lib/../lib] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] + arg [CMakeFiles/cmTryCompileExec1351686098.dir/CMakeCXXCompilerABI.cpp.o] ==> ignore + arg [-lstdc++] ==> lib [stdc++] + arg [-lm] ==> lib [m] + arg [-lgcc_s] ==> lib [gcc_s] + arg [-lgcc] ==> lib [gcc] + arg [-lc] ==> lib [c] + arg [-lgcc_s] ==> lib [gcc_s] + arg [-lgcc] ==> lib [gcc] + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o] ==> ignore + remove lib [gcc_s] + remove lib [gcc] + remove lib [gcc_s] + remove lib [gcc] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8] ==> [/usr/lib/gcc/x86_64-linux-gnu/4.8] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] ==> [/usr/lib] + collapse library dir [/lib/x86_64-linux-gnu] ==> [/lib/x86_64-linux-gnu] + collapse library dir [/lib/../lib] ==> [/lib] + collapse library dir [/usr/lib/x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/../lib] ==> [/usr/lib] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] ==> [/usr/lib] + implicit libs: [stdc++;m;c] + implicit dirs: [/usr/lib/gcc/x86_64-linux-gnu/4.8;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib] + implicit fwks: [] + + diff --git a/vSLAM/ch8/LKFlow/build/CMakeFiles/Makefile.cmake b/vSLAM/ch8/LKFlow/build/CMakeFiles/Makefile.cmake new file mode 100644 index 00000000..153b16ce --- /dev/null +++ b/vSLAM/ch8/LKFlow/build/CMakeFiles/Makefile.cmake @@ -0,0 +1,72 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# The generator used is: +SET(CMAKE_DEPENDS_GENERATOR "Unix Makefiles") + +# The top level Makefile was generated from the following files: +SET(CMAKE_MAKEFILE_DEPENDS + "CMakeCache.txt" + "../CMakeLists.txt" + "CMakeFiles/2.8.12.2/CMakeCCompiler.cmake" + "CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake" + "CMakeFiles/2.8.12.2/CMakeSystem.cmake" + "/usr/local/share/OpenCV/OpenCVConfig-version.cmake" + "/usr/local/share/OpenCV/OpenCVConfig.cmake" + "/usr/local/share/OpenCV/OpenCVModules-release.cmake" + "/usr/local/share/OpenCV/OpenCVModules.cmake" + "/usr/share/cmake-2.8/Modules/CMakeCCompiler.cmake.in" + "/usr/share/cmake-2.8/Modules/CMakeCCompilerABI.c" + "/usr/share/cmake-2.8/Modules/CMakeCInformation.cmake" + "/usr/share/cmake-2.8/Modules/CMakeCXXCompiler.cmake.in" + "/usr/share/cmake-2.8/Modules/CMakeCXXCompilerABI.cpp" + "/usr/share/cmake-2.8/Modules/CMakeCXXInformation.cmake" + "/usr/share/cmake-2.8/Modules/CMakeClDeps.cmake" + "/usr/share/cmake-2.8/Modules/CMakeCommonLanguageInclude.cmake" + "/usr/share/cmake-2.8/Modules/CMakeDetermineCCompiler.cmake" + "/usr/share/cmake-2.8/Modules/CMakeDetermineCXXCompiler.cmake" + "/usr/share/cmake-2.8/Modules/CMakeDetermineCompiler.cmake" + "/usr/share/cmake-2.8/Modules/CMakeDetermineCompilerABI.cmake" + "/usr/share/cmake-2.8/Modules/CMakeDetermineCompilerId.cmake" + "/usr/share/cmake-2.8/Modules/CMakeDetermineSystem.cmake" + "/usr/share/cmake-2.8/Modules/CMakeFindBinUtils.cmake" + "/usr/share/cmake-2.8/Modules/CMakeGenericSystem.cmake" + "/usr/share/cmake-2.8/Modules/CMakeParseImplicitLinkInfo.cmake" + "/usr/share/cmake-2.8/Modules/CMakeSystem.cmake.in" + "/usr/share/cmake-2.8/Modules/CMakeSystemSpecificInformation.cmake" + "/usr/share/cmake-2.8/Modules/CMakeTestCCompiler.cmake" + "/usr/share/cmake-2.8/Modules/CMakeTestCXXCompiler.cmake" + "/usr/share/cmake-2.8/Modules/CMakeTestCompilerCommon.cmake" + "/usr/share/cmake-2.8/Modules/CMakeUnixFindMake.cmake" + "/usr/share/cmake-2.8/Modules/Compiler/GNU-C.cmake" + "/usr/share/cmake-2.8/Modules/Compiler/GNU-CXX.cmake" + "/usr/share/cmake-2.8/Modules/Compiler/GNU.cmake" + "/usr/share/cmake-2.8/Modules/MultiArchCross.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux-CXX.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux-GNU-C.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux-GNU-CXX.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux-GNU.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux.cmake" + "/usr/share/cmake-2.8/Modules/Platform/UnixPaths.cmake" + ) + +# The corresponding makefile is: +SET(CMAKE_MAKEFILE_OUTPUTS + "Makefile" + "CMakeFiles/cmake.check_cache" + ) + +# Byproducts of CMake generate step: +SET(CMAKE_MAKEFILE_PRODUCTS + "CMakeFiles/2.8.12.2/CMakeSystem.cmake" + "CMakeFiles/2.8.12.2/CMakeCCompiler.cmake" + "CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake" + "CMakeFiles/2.8.12.2/CMakeCCompiler.cmake" + "CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake" + "CMakeFiles/CMakeDirectoryInformation.cmake" + ) + +# Dependency information for all targets: +SET(CMAKE_DEPEND_INFO_FILES + "CMakeFiles/useLK.dir/DependInfo.cmake" + ) diff --git a/vSLAM/ch8/LKFlow/build/CMakeFiles/Makefile2 b/vSLAM/ch8/LKFlow/build/CMakeFiles/Makefile2 new file mode 100644 index 00000000..8630e5fe --- /dev/null +++ b/vSLAM/ch8/LKFlow/build/CMakeFiles/Makefile2 @@ -0,0 +1,99 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Default target executed when no arguments are given to make. +default_target: all +.PHONY : default_target + +# The main recursive all target +all: +.PHONY : all + +# The main recursive preinstall target +preinstall: +.PHONY : preinstall + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build + +#============================================================================= +# Target rules for target CMakeFiles/useLK.dir + +# All Build rule for target. +CMakeFiles/useLK.dir/all: + $(MAKE) -f CMakeFiles/useLK.dir/build.make CMakeFiles/useLK.dir/depend + $(MAKE) -f CMakeFiles/useLK.dir/build.make CMakeFiles/useLK.dir/build + $(CMAKE_COMMAND) -E cmake_progress_report /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles 1 + @echo "Built target useLK" +.PHONY : CMakeFiles/useLK.dir/all + +# Include target in all. +all: CMakeFiles/useLK.dir/all +.PHONY : all + +# Build rule for subdir invocation for target. +CMakeFiles/useLK.dir/rule: cmake_check_build_system + $(CMAKE_COMMAND) -E cmake_progress_start /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles 1 + $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/useLK.dir/all + $(CMAKE_COMMAND) -E cmake_progress_start /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles 0 +.PHONY : CMakeFiles/useLK.dir/rule + +# Convenience name for target. +useLK: CMakeFiles/useLK.dir/rule +.PHONY : useLK + +# clean rule for target. +CMakeFiles/useLK.dir/clean: + $(MAKE) -f CMakeFiles/useLK.dir/build.make CMakeFiles/useLK.dir/clean +.PHONY : CMakeFiles/useLK.dir/clean + +# clean rule for target. +clean: CMakeFiles/useLK.dir/clean +.PHONY : clean + +#============================================================================= +# Special targets to cleanup operation of make. + +# Special rule to run CMake to check the build system integrity. +# No rule that depends on this can have commands that come from listfiles +# because they might be regenerated. +cmake_check_build_system: + $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0 +.PHONY : cmake_check_build_system + diff --git a/vSLAM/ch8/LKFlow/build/CMakeFiles/TargetDirectories.txt b/vSLAM/ch8/LKFlow/build/CMakeFiles/TargetDirectories.txt new file mode 100644 index 00000000..dc782e0b --- /dev/null +++ b/vSLAM/ch8/LKFlow/build/CMakeFiles/TargetDirectories.txt @@ -0,0 +1 @@ +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir diff --git a/vSLAM/ch8/LKFlow/build/CMakeFiles/cmake.check_cache b/vSLAM/ch8/LKFlow/build/CMakeFiles/cmake.check_cache new file mode 100644 index 00000000..3dccd731 --- /dev/null +++ b/vSLAM/ch8/LKFlow/build/CMakeFiles/cmake.check_cache @@ -0,0 +1 @@ +# This file is generated by cmake for dependency checking of the CMakeCache.txt file diff --git a/vSLAM/ch8/LKFlow/build/CMakeFiles/progress.marks b/vSLAM/ch8/LKFlow/build/CMakeFiles/progress.marks new file mode 100644 index 00000000..d00491fd --- /dev/null +++ b/vSLAM/ch8/LKFlow/build/CMakeFiles/progress.marks @@ -0,0 +1 @@ +1 diff --git a/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/CXX.includecache b/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/CXX.includecache new file mode 100644 index 00000000..6b87d7c6 --- /dev/null +++ b/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/CXX.includecache @@ -0,0 +1,486 @@ +#IncludeRegexLine: ^[ ]*#[ ]*(include|import)[ ]*[<"]([^">]+)([">]) + +#IncludeRegexScan: ^.*$ + +#IncludeRegexComplain: ^$ + +#IncludeRegexTransform: + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/useLK.cpp +iostream +- +fstream +- +list +- +vector +- +chrono +- +opencv2/core/core.hpp +- +opencv2/highgui/highgui.hpp +- +opencv2/features2d/features2d.hpp +- +opencv2/video/tracking.hpp +- + +/usr/local/include/opencv/cxcore.h +opencv2/core/core_c.h +/usr/local/include/opencv/opencv2/core/core_c.h + +/usr/local/include/opencv2/calib3d.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/opencv2/features2d.hpp +opencv2/core/affine.hpp +/usr/local/include/opencv2/opencv2/core/affine.hpp +opencv2/calib3d/calib3d_c.h +/usr/local/include/opencv2/opencv2/calib3d/calib3d_c.h + +/usr/local/include/opencv2/calib3d/calib3d_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/calib3d/opencv2/core/core_c.h + +/usr/local/include/opencv2/core.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/opencv2/core/cvdef.h +opencv2/core/version.hpp +/usr/local/include/opencv2/opencv2/core/version.hpp +opencv2/core/base.hpp +/usr/local/include/opencv2/opencv2/core/base.hpp +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/opencv2/core/cvstd.hpp +opencv2/core/traits.hpp +/usr/local/include/opencv2/opencv2/core/traits.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/opencv2/core/matx.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/opencv2/core/types.hpp +opencv2/core/mat.hpp +/usr/local/include/opencv2/opencv2/core/mat.hpp +opencv2/core/persistence.hpp +/usr/local/include/opencv2/opencv2/core/persistence.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/opencv2/opencv.hpp +opencv2/xfeatures2d.hpp +/usr/local/include/opencv2/opencv2/xfeatures2d.hpp +opencv2/core/operations.hpp +/usr/local/include/opencv2/opencv2/core/operations.hpp +opencv2/core/cvstd.inl.hpp +/usr/local/include/opencv2/opencv2/core/cvstd.inl.hpp +opencv2/core/utility.hpp +/usr/local/include/opencv2/opencv2/core/utility.hpp +opencv2/core/optim.hpp +/usr/local/include/opencv2/opencv2/core/optim.hpp + +/usr/local/include/opencv2/core/affine.hpp +opencv2/core.hpp +- + +/usr/local/include/opencv2/core/base.hpp +climits +- +algorithm +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/core/opencv2/core/cvstd.hpp +opencv2/core/neon_utils.hpp +/usr/local/include/opencv2/core/opencv2/core/neon_utils.hpp + +/usr/local/include/opencv2/core/bufferpool.hpp + +/usr/local/include/opencv2/core/core.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/core_c.h +opencv2/core/types_c.h +/usr/local/include/opencv2/core/opencv2/core/types_c.h +cxcore.h +/usr/local/include/opencv2/core/cxcore.h +cxcore.h +/usr/local/include/opencv2/core/cxcore.h +opencv2/core/utility.hpp +/usr/local/include/opencv2/core/opencv2/core/utility.hpp + +/usr/local/include/opencv2/core/cvdef.h +limits.h +- +opencv2/core/hal/interface.h +/usr/local/include/opencv2/core/opencv2/core/hal/interface.h +emmintrin.h +- +pmmintrin.h +- +tmmintrin.h +- +smmintrin.h +- +nmmintrin.h +- +nmmintrin.h +- +popcntintrin.h +- +immintrin.h +- +immintrin.h +- +Intrin.h +- +arm_neon.h +/usr/local/include/opencv2/core/arm_neon.h +arm_neon.h +- +intrin.h +- + +/usr/local/include/opencv2/core/cvstd.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +cstddef +- +cstring +- +cctype +- +string +- +algorithm +- +utility +- +cstdlib +- +cmath +- +opencv2/core/ptr.inl.hpp +/usr/local/include/opencv2/core/opencv2/core/ptr.inl.hpp + +/usr/local/include/opencv2/core/cvstd.inl.hpp +complex +- +ostream +- + +/usr/local/include/opencv2/core/fast_math.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +fastmath.h +- +cmath +- +math.h +- +tegra_round.hpp +/usr/local/include/opencv2/core/tegra_round.hpp + +/usr/local/include/opencv2/core/hal/interface.h +cstddef +- +stddef.h +- +cstdint +- +stdint.h +- + +/usr/local/include/opencv2/core/mat.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/core/opencv2/core/matx.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/core/opencv2/core/types.hpp +opencv2/core/bufferpool.hpp +/usr/local/include/opencv2/core/opencv2/core/bufferpool.hpp +opencv2/core/mat.inl.hpp +/usr/local/include/opencv2/core/opencv2/core/mat.inl.hpp + +/usr/local/include/opencv2/core/mat.inl.hpp + +/usr/local/include/opencv2/core/matx.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/base.hpp +/usr/local/include/opencv2/core/opencv2/core/base.hpp +opencv2/core/traits.hpp +/usr/local/include/opencv2/core/opencv2/core/traits.hpp +opencv2/core/saturate.hpp +/usr/local/include/opencv2/core/opencv2/core/saturate.hpp + +/usr/local/include/opencv2/core/neon_utils.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h + +/usr/local/include/opencv2/core/operations.hpp +cstdio +- + +/usr/local/include/opencv2/core/optim.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/persistence.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/core/opencv2/core/types.hpp +opencv2/core/mat.hpp +/usr/local/include/opencv2/core/opencv2/core/mat.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/core/opencv2/opencv.hpp +time.h +- + +/usr/local/include/opencv2/core/ptr.inl.hpp +algorithm +- + +/usr/local/include/opencv2/core/saturate.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/fast_math.hpp +/usr/local/include/opencv2/core/opencv2/core/fast_math.hpp + +/usr/local/include/opencv2/core/traits.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h + +/usr/local/include/opencv2/core/types.hpp +climits +- +cfloat +- +vector +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/core/opencv2/core/cvstd.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/core/opencv2/core/matx.hpp + +/usr/local/include/opencv2/core/types_c.h +ipl.h +- +ipl/ipl.h +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +assert.h +- +stdlib.h +- +string.h +- +float.h +- +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/utility.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp +opencv2/core/core_c.h +/usr/local/include/opencv2/core/opencv2/core/core_c.h + +/usr/local/include/opencv2/core/version.hpp + +/usr/local/include/opencv2/features2d.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/flann/miniflann.hpp +/usr/local/include/opencv2/opencv2/flann/miniflann.hpp + +/usr/local/include/opencv2/features2d/features2d.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/features2d/opencv2/features2d.hpp + +/usr/local/include/opencv2/flann/config.h + +/usr/local/include/opencv2/flann/defines.h +config.h +/usr/local/include/opencv2/flann/config.h + +/usr/local/include/opencv2/flann/miniflann.hpp +opencv2/core.hpp +/usr/local/include/opencv2/flann/opencv2/core.hpp +opencv2/flann/defines.h +/usr/local/include/opencv2/flann/opencv2/flann/defines.h + +/usr/local/include/opencv2/highgui.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgcodecs.hpp +/usr/local/include/opencv2/opencv2/imgcodecs.hpp +opencv2/videoio.hpp +/usr/local/include/opencv2/opencv2/videoio.hpp +opencv2/highgui/highgui_c.h +/usr/local/include/opencv2/opencv2/highgui/highgui_c.h + +/usr/local/include/opencv2/highgui/highgui.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/highgui/opencv2/highgui.hpp + +/usr/local/include/opencv2/highgui/highgui_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/highgui/opencv2/core/core_c.h +opencv2/imgproc/imgproc_c.h +/usr/local/include/opencv2/highgui/opencv2/imgproc/imgproc_c.h +opencv2/imgcodecs/imgcodecs_c.h +/usr/local/include/opencv2/highgui/opencv2/imgcodecs/imgcodecs_c.h +opencv2/videoio/videoio_c.h +/usr/local/include/opencv2/highgui/opencv2/videoio/videoio_c.h + +/usr/local/include/opencv2/imgcodecs.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/opencv.hpp +- + +/usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/imgcodecs/opencv2/core/core_c.h + +/usr/local/include/opencv2/imgproc.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/core.hpp +- +opencv2/imgproc.hpp +- +opencv2/imgcodecs.hpp +- +opencv2/highgui.hpp +- +iostream +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +math.h +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/opencv2/highgui.hpp +opencv2/imgproc/imgproc_c.h +/usr/local/include/opencv2/opencv2/imgproc/imgproc_c.h + +/usr/local/include/opencv2/imgproc/imgproc_c.h +opencv2/imgproc/types_c.h +/usr/local/include/opencv2/imgproc/opencv2/imgproc/types_c.h + +/usr/local/include/opencv2/imgproc/types_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/imgproc/opencv2/core/core_c.h + +/usr/local/include/opencv2/ml.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +float.h +- +map +- +iostream +- + +/usr/local/include/opencv2/objdetect.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/objdetect/detection_based_tracker.hpp +/usr/local/include/opencv2/opencv2/objdetect/detection_based_tracker.hpp +opencv2/objdetect/objdetect_c.h +/usr/local/include/opencv2/opencv2/objdetect/objdetect_c.h + +/usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +vector +- + +/usr/local/include/opencv2/objdetect/objdetect_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/objdetect/opencv2/core/core_c.h +deque +- +vector +- + +/usr/local/include/opencv2/opencv.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/photo.hpp +/usr/local/include/opencv2/opencv2/photo.hpp +opencv2/video.hpp +/usr/local/include/opencv2/opencv2/video.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/opencv2/features2d.hpp +opencv2/objdetect.hpp +/usr/local/include/opencv2/opencv2/objdetect.hpp +opencv2/calib3d.hpp +/usr/local/include/opencv2/opencv2/calib3d.hpp +opencv2/imgcodecs.hpp +/usr/local/include/opencv2/opencv2/imgcodecs.hpp +opencv2/videoio.hpp +/usr/local/include/opencv2/opencv2/videoio.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/opencv2/highgui.hpp +opencv2/ml.hpp +/usr/local/include/opencv2/opencv2/ml.hpp + +/usr/local/include/opencv2/photo.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/photo/photo_c.h +/usr/local/include/opencv2/opencv2/photo/photo_c.h + +/usr/local/include/opencv2/photo/photo_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/photo/opencv2/core/core_c.h + +/usr/local/include/opencv2/video.hpp +opencv2/video/tracking.hpp +/usr/local/include/opencv2/opencv2/video/tracking.hpp +opencv2/video/background_segm.hpp +/usr/local/include/opencv2/opencv2/video/background_segm.hpp +opencv2/video/tracking_c.h +/usr/local/include/opencv2/opencv2/video/tracking_c.h + +/usr/local/include/opencv2/video/background_segm.hpp +opencv2/core.hpp +/usr/local/include/opencv2/video/opencv2/core.hpp + +/usr/local/include/opencv2/video/tracking.hpp +opencv2/core.hpp +/usr/local/include/opencv2/video/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/video/opencv2/imgproc.hpp + +/usr/local/include/opencv2/video/tracking_c.h +opencv2/imgproc/types_c.h +/usr/local/include/opencv2/video/opencv2/imgproc/types_c.h + +/usr/local/include/opencv2/videoio.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/opencv2/opencv.hpp + +/usr/local/include/opencv2/videoio/videoio_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/videoio/opencv2/core/core_c.h + diff --git a/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/DependInfo.cmake b/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/DependInfo.cmake new file mode 100644 index 00000000..32bc9ade --- /dev/null +++ b/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/DependInfo.cmake @@ -0,0 +1,22 @@ +# The set of languages for which implicit dependencies are needed: +SET(CMAKE_DEPENDS_LANGUAGES + "CXX" + ) +# The set of files for implicit dependencies of each language: +SET(CMAKE_DEPENDS_CHECK_CXX + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/useLK.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/useLK.cpp.o" + ) +SET(CMAKE_CXX_COMPILER_ID "GNU") + +# Targets to which this target links. +SET(CMAKE_TARGET_LINKED_INFO_FILES + ) + +# The include file search paths: +SET(CMAKE_C_TARGET_INCLUDE_PATH + "/usr/local/include/opencv" + "/usr/local/include" + ) +SET(CMAKE_CXX_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) +SET(CMAKE_Fortran_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) +SET(CMAKE_ASM_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) diff --git a/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/build.make b/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/build.make new file mode 100644 index 00000000..f957310f --- /dev/null +++ b/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/build.make @@ -0,0 +1,128 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build + +# Include any dependencies generated for this target. +include CMakeFiles/useLK.dir/depend.make + +# Include the progress variables for this target. +include CMakeFiles/useLK.dir/progress.make + +# Include the compile flags for this target's objects. +include CMakeFiles/useLK.dir/flags.make + +CMakeFiles/useLK.dir/useLK.cpp.o: CMakeFiles/useLK.dir/flags.make +CMakeFiles/useLK.dir/useLK.cpp.o: ../useLK.cpp + $(CMAKE_COMMAND) -E cmake_progress_report /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles $(CMAKE_PROGRESS_1) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object CMakeFiles/useLK.dir/useLK.cpp.o" + /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/useLK.dir/useLK.cpp.o -c /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/useLK.cpp + +CMakeFiles/useLK.dir/useLK.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/useLK.dir/useLK.cpp.i" + /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -E /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/useLK.cpp > CMakeFiles/useLK.dir/useLK.cpp.i + +CMakeFiles/useLK.dir/useLK.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/useLK.dir/useLK.cpp.s" + /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -S /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/useLK.cpp -o CMakeFiles/useLK.dir/useLK.cpp.s + +CMakeFiles/useLK.dir/useLK.cpp.o.requires: +.PHONY : CMakeFiles/useLK.dir/useLK.cpp.o.requires + +CMakeFiles/useLK.dir/useLK.cpp.o.provides: CMakeFiles/useLK.dir/useLK.cpp.o.requires + $(MAKE) -f CMakeFiles/useLK.dir/build.make CMakeFiles/useLK.dir/useLK.cpp.o.provides.build +.PHONY : CMakeFiles/useLK.dir/useLK.cpp.o.provides + +CMakeFiles/useLK.dir/useLK.cpp.o.provides.build: CMakeFiles/useLK.dir/useLK.cpp.o + +# Object files for target useLK +useLK_OBJECTS = \ +"CMakeFiles/useLK.dir/useLK.cpp.o" + +# External object files for target useLK +useLK_EXTERNAL_OBJECTS = + +useLK: CMakeFiles/useLK.dir/useLK.cpp.o +useLK: CMakeFiles/useLK.dir/build.make +useLK: /usr/local/lib/libopencv_viz.so.3.1.0 +useLK: /usr/local/lib/libopencv_videostab.so.3.1.0 +useLK: /usr/local/lib/libopencv_videoio.so.3.1.0 +useLK: /usr/local/lib/libopencv_video.so.3.1.0 +useLK: /usr/local/lib/libopencv_superres.so.3.1.0 +useLK: /usr/local/lib/libopencv_stitching.so.3.1.0 +useLK: /usr/local/lib/libopencv_shape.so.3.1.0 +useLK: /usr/local/lib/libopencv_photo.so.3.1.0 +useLK: /usr/local/lib/libopencv_objdetect.so.3.1.0 +useLK: /usr/local/lib/libopencv_ml.so.3.1.0 +useLK: /usr/local/lib/libopencv_imgproc.so.3.1.0 +useLK: /usr/local/lib/libopencv_imgcodecs.so.3.1.0 +useLK: /usr/local/lib/libopencv_highgui.so.3.1.0 +useLK: /usr/local/lib/libopencv_flann.so.3.1.0 +useLK: /usr/local/lib/libopencv_features2d.so.3.1.0 +useLK: /usr/local/lib/libopencv_core.so.3.1.0 +useLK: /usr/local/lib/libopencv_calib3d.so.3.1.0 +useLK: /usr/local/lib/libopencv_features2d.so.3.1.0 +useLK: /usr/local/lib/libopencv_ml.so.3.1.0 +useLK: /usr/local/lib/libopencv_highgui.so.3.1.0 +useLK: /usr/local/lib/libopencv_videoio.so.3.1.0 +useLK: /usr/local/lib/libopencv_imgcodecs.so.3.1.0 +useLK: /usr/local/lib/libopencv_flann.so.3.1.0 +useLK: /usr/local/lib/libopencv_video.so.3.1.0 +useLK: /usr/local/lib/libopencv_imgproc.so.3.1.0 +useLK: /usr/local/lib/libopencv_core.so.3.1.0 +useLK: CMakeFiles/useLK.dir/link.txt + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --red --bold "Linking CXX executable useLK" + $(CMAKE_COMMAND) -E cmake_link_script CMakeFiles/useLK.dir/link.txt --verbose=$(VERBOSE) + +# Rule to build all files generated by this target. +CMakeFiles/useLK.dir/build: useLK +.PHONY : CMakeFiles/useLK.dir/build + +CMakeFiles/useLK.dir/requires: CMakeFiles/useLK.dir/useLK.cpp.o.requires +.PHONY : CMakeFiles/useLK.dir/requires + +CMakeFiles/useLK.dir/clean: + $(CMAKE_COMMAND) -P CMakeFiles/useLK.dir/cmake_clean.cmake +.PHONY : CMakeFiles/useLK.dir/clean + +CMakeFiles/useLK.dir/depend: + cd /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/DependInfo.cmake --color=$(COLOR) +.PHONY : CMakeFiles/useLK.dir/depend + diff --git a/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/cmake_clean.cmake b/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/cmake_clean.cmake new file mode 100644 index 00000000..dbfc3681 --- /dev/null +++ b/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/cmake_clean.cmake @@ -0,0 +1,10 @@ +FILE(REMOVE_RECURSE + "CMakeFiles/useLK.dir/useLK.cpp.o" + "useLK.pdb" + "useLK" +) + +# Per-language clean rules from dependency scanning. +FOREACH(lang CXX) + INCLUDE(CMakeFiles/useLK.dir/cmake_clean_${lang}.cmake OPTIONAL) +ENDFOREACH(lang) diff --git a/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/depend.internal b/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/depend.internal new file mode 100644 index 00000000..b6a10588 --- /dev/null +++ b/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/depend.internal @@ -0,0 +1,59 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +CMakeFiles/useLK.dir/useLK.cpp.o + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/useLK.cpp + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/features2d/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h diff --git a/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/depend.make b/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/depend.make new file mode 100644 index 00000000..058a6756 --- /dev/null +++ b/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/depend.make @@ -0,0 +1,59 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +CMakeFiles/useLK.dir/useLK.cpp.o: ../useLK.cpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv/cxcore.h +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/calib3d.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/core.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/core/affine.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/core/base.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/core/core.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/core/core_c.h +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/core/cvdef.h +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/core/mat.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/core/matx.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/core/operations.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/core/optim.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/core/traits.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/core/types.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/core/types_c.h +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/core/utility.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/core/version.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/features2d.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/features2d/features2d.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/flann/config.h +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/flann/defines.h +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/highgui.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/highgui/highgui.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/imgproc.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/ml.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/objdetect.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/opencv.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/photo.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/video.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/videoio.hpp +CMakeFiles/useLK.dir/useLK.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + diff --git a/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/flags.make b/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/flags.make new file mode 100644 index 00000000..f46ef0aa --- /dev/null +++ b/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/flags.make @@ -0,0 +1,8 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# compile CXX with /usr/bin/c++ +CXX_FLAGS = -std=c++11 -O3 -O3 -DNDEBUG -I/usr/local/include/opencv -I/usr/local/include + +CXX_DEFINES = + diff --git a/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/link.txt b/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/link.txt new file mode 100644 index 00000000..95a68541 --- /dev/null +++ b/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/link.txt @@ -0,0 +1 @@ +/usr/bin/c++ -std=c++11 -O3 -O3 -DNDEBUG CMakeFiles/useLK.dir/useLK.cpp.o -o useLK -rdynamic /usr/local/lib/libopencv_viz.so.3.1.0 /usr/local/lib/libopencv_videostab.so.3.1.0 /usr/local/lib/libopencv_videoio.so.3.1.0 /usr/local/lib/libopencv_video.so.3.1.0 /usr/local/lib/libopencv_superres.so.3.1.0 /usr/local/lib/libopencv_stitching.so.3.1.0 /usr/local/lib/libopencv_shape.so.3.1.0 /usr/local/lib/libopencv_photo.so.3.1.0 /usr/local/lib/libopencv_objdetect.so.3.1.0 /usr/local/lib/libopencv_ml.so.3.1.0 /usr/local/lib/libopencv_imgproc.so.3.1.0 /usr/local/lib/libopencv_imgcodecs.so.3.1.0 /usr/local/lib/libopencv_highgui.so.3.1.0 /usr/local/lib/libopencv_flann.so.3.1.0 /usr/local/lib/libopencv_features2d.so.3.1.0 /usr/local/lib/libopencv_core.so.3.1.0 /usr/local/lib/libopencv_calib3d.so.3.1.0 /usr/local/lib/libopencv_features2d.so.3.1.0 /usr/local/lib/libopencv_ml.so.3.1.0 /usr/local/lib/libopencv_highgui.so.3.1.0 /usr/local/lib/libopencv_videoio.so.3.1.0 /usr/local/lib/libopencv_imgcodecs.so.3.1.0 /usr/local/lib/libopencv_flann.so.3.1.0 /usr/local/lib/libopencv_video.so.3.1.0 /usr/local/lib/libopencv_imgproc.so.3.1.0 /usr/local/lib/libopencv_core.so.3.1.0 -Wl,-rpath,/usr/local/lib diff --git a/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/progress.make b/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/progress.make new file mode 100644 index 00000000..781c7de2 --- /dev/null +++ b/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/progress.make @@ -0,0 +1,2 @@ +CMAKE_PROGRESS_1 = 1 + diff --git a/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/useLK.cpp.o b/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/useLK.cpp.o new file mode 100644 index 00000000..598dc8ef Binary files /dev/null and b/vSLAM/ch8/LKFlow/build/CMakeFiles/useLK.dir/useLK.cpp.o differ diff --git a/vSLAM/ch8/LKFlow/build/Makefile b/vSLAM/ch8/LKFlow/build/Makefile new file mode 100644 index 00000000..eb956cfb --- /dev/null +++ b/vSLAM/ch8/LKFlow/build/Makefile @@ -0,0 +1,163 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Default target executed when no arguments are given to make. +default_target: all +.PHONY : default_target + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build + +#============================================================================= +# Targets provided globally by CMake. + +# Special rule for the target edit_cache +edit_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running interactive CMake command-line interface..." + /usr/bin/cmake -i . +.PHONY : edit_cache + +# Special rule for the target edit_cache +edit_cache/fast: edit_cache +.PHONY : edit_cache/fast + +# Special rule for the target rebuild_cache +rebuild_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake to regenerate build system..." + /usr/bin/cmake -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) +.PHONY : rebuild_cache + +# Special rule for the target rebuild_cache +rebuild_cache/fast: rebuild_cache +.PHONY : rebuild_cache/fast + +# The main all target +all: cmake_check_build_system + $(CMAKE_COMMAND) -E cmake_progress_start /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles/progress.marks + $(MAKE) -f CMakeFiles/Makefile2 all + $(CMAKE_COMMAND) -E cmake_progress_start /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/CMakeFiles 0 +.PHONY : all + +# The main clean target +clean: + $(MAKE) -f CMakeFiles/Makefile2 clean +.PHONY : clean + +# The main clean target +clean/fast: clean +.PHONY : clean/fast + +# Prepare targets for installation. +preinstall: all + $(MAKE) -f CMakeFiles/Makefile2 preinstall +.PHONY : preinstall + +# Prepare targets for installation. +preinstall/fast: + $(MAKE) -f CMakeFiles/Makefile2 preinstall +.PHONY : preinstall/fast + +# clear depends +depend: + $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 1 +.PHONY : depend + +#============================================================================= +# Target rules for targets named useLK + +# Build rule for target. +useLK: cmake_check_build_system + $(MAKE) -f CMakeFiles/Makefile2 useLK +.PHONY : useLK + +# fast build rule for target. +useLK/fast: + $(MAKE) -f CMakeFiles/useLK.dir/build.make CMakeFiles/useLK.dir/build +.PHONY : useLK/fast + +useLK.o: useLK.cpp.o +.PHONY : useLK.o + +# target to build an object file +useLK.cpp.o: + $(MAKE) -f CMakeFiles/useLK.dir/build.make CMakeFiles/useLK.dir/useLK.cpp.o +.PHONY : useLK.cpp.o + +useLK.i: useLK.cpp.i +.PHONY : useLK.i + +# target to preprocess a source file +useLK.cpp.i: + $(MAKE) -f CMakeFiles/useLK.dir/build.make CMakeFiles/useLK.dir/useLK.cpp.i +.PHONY : useLK.cpp.i + +useLK.s: useLK.cpp.s +.PHONY : useLK.s + +# target to generate assembly for a file +useLK.cpp.s: + $(MAKE) -f CMakeFiles/useLK.dir/build.make CMakeFiles/useLK.dir/useLK.cpp.s +.PHONY : useLK.cpp.s + +# Help Target +help: + @echo "The following are some of the valid targets for this Makefile:" + @echo "... all (the default if no target is provided)" + @echo "... clean" + @echo "... depend" + @echo "... edit_cache" + @echo "... rebuild_cache" + @echo "... useLK" + @echo "... useLK.o" + @echo "... useLK.i" + @echo "... useLK.s" +.PHONY : help + + + +#============================================================================= +# Special targets to cleanup operation of make. + +# Special rule to run CMake to check the build system integrity. +# No rule that depends on this can have commands that come from listfiles +# because they might be regenerated. +cmake_check_build_system: + $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0 +.PHONY : cmake_check_build_system + diff --git a/vSLAM/ch8/LKFlow/build/cmake_install.cmake b/vSLAM/ch8/LKFlow/build/cmake_install.cmake new file mode 100644 index 00000000..c7f020a4 --- /dev/null +++ b/vSLAM/ch8/LKFlow/build/cmake_install.cmake @@ -0,0 +1,44 @@ +# Install script for directory: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow + +# Set the install prefix +IF(NOT DEFINED CMAKE_INSTALL_PREFIX) + SET(CMAKE_INSTALL_PREFIX "/usr/local") +ENDIF(NOT DEFINED CMAKE_INSTALL_PREFIX) +STRING(REGEX REPLACE "/$" "" CMAKE_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}") + +# Set the install configuration name. +IF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + IF(BUILD_TYPE) + STRING(REGEX REPLACE "^[^A-Za-z0-9_]+" "" + CMAKE_INSTALL_CONFIG_NAME "${BUILD_TYPE}") + ELSE(BUILD_TYPE) + SET(CMAKE_INSTALL_CONFIG_NAME "Release") + ENDIF(BUILD_TYPE) + MESSAGE(STATUS "Install configuration: \"${CMAKE_INSTALL_CONFIG_NAME}\"") +ENDIF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + +# Set the component getting installed. +IF(NOT CMAKE_INSTALL_COMPONENT) + IF(COMPONENT) + MESSAGE(STATUS "Install component: \"${COMPONENT}\"") + SET(CMAKE_INSTALL_COMPONENT "${COMPONENT}") + ELSE(COMPONENT) + SET(CMAKE_INSTALL_COMPONENT) + ENDIF(COMPONENT) +ENDIF(NOT CMAKE_INSTALL_COMPONENT) + +# Install shared libraries without execute permission? +IF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + SET(CMAKE_INSTALL_SO_NO_EXE "1") +ENDIF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + +IF(CMAKE_INSTALL_COMPONENT) + SET(CMAKE_INSTALL_MANIFEST "install_manifest_${CMAKE_INSTALL_COMPONENT}.txt") +ELSE(CMAKE_INSTALL_COMPONENT) + SET(CMAKE_INSTALL_MANIFEST "install_manifest.txt") +ENDIF(CMAKE_INSTALL_COMPONENT) + +FILE(WRITE "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/${CMAKE_INSTALL_MANIFEST}" "") +FOREACH(file ${CMAKE_INSTALL_MANIFEST_FILES}) + FILE(APPEND "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/LKFlow/build/${CMAKE_INSTALL_MANIFEST}" "${file}\n") +ENDFOREACH(file) diff --git a/vSLAM/ch8/LKFlow/build/useLK b/vSLAM/ch8/LKFlow/build/useLK new file mode 100755 index 00000000..6d9e99ae Binary files /dev/null and b/vSLAM/ch8/LKFlow/build/useLK differ diff --git a/vSLAM/ch8/LKFlow/useLK.cpp b/vSLAM/ch8/LKFlow/useLK.cpp index 5dbfeae1..370ce8e4 100644 --- a/vSLAM/ch8/LKFlow/useLK.cpp +++ b/vSLAM/ch8/LKFlow/useLK.cpp @@ -1,5 +1,9 @@ +/* + * LK光流法跟踪特征点 + * ./useLK ../../data + */ #include -#include +#include //文件数据流 #include #include #include @@ -8,7 +12,7 @@ using namespace std; #include #include #include -#include +#include //跟踪算法 int main( int argc, char** argv ) { @@ -21,7 +25,7 @@ int main( int argc, char** argv ) string associate_file = path_to_dataset + "/associate.txt"; ifstream fin( associate_file ); - if ( !fin ) + if ( !fin ) //打开文件失败 { cerr<<"I cann't find associate.txt!"<>time_rgb>>rgb_file>>time_depth>>depth_file; + //rgb图像对应时间 rgb图像 深度图像对应时间 深度图像 color = cv::imread( path_to_dataset+"/"+rgb_file ); depth = cv::imread( path_to_dataset+"/"+depth_file, -1 ); - if (index ==0 ) + if (index ==0 )//第一帧图像 { // 对第一帧提取FAST特征点 vector kps; @@ -50,8 +55,8 @@ int main( int argc, char** argv ) if ( color.data==nullptr || depth.data==nullptr ) continue; // 对其他帧用LK跟踪特征点 - vector next_keypoints; - vector prev_keypoints; + vector next_keypoints; //下一帧关键点 + vector prev_keypoints; //上一帧关键点 for ( auto kp:keypoints ) prev_keypoints.push_back(kp); vector status; @@ -84,7 +89,7 @@ int main( int argc, char** argv ) for ( auto kp:keypoints ) cv::circle(img_show, kp, 10, cv::Scalar(0, 240, 0), 1); cv::imshow("corners", img_show); - cv::waitKey(0); + cv::waitKey(0);//等待按键按下 遍历下一张图片 last_color = color; } return 0; diff --git a/vSLAM/ch8/data/associate.py b/vSLAM/ch8/data/associate.py new file mode 100644 index 00000000..32521c1a --- /dev/null +++ b/vSLAM/ch8/data/associate.py @@ -0,0 +1,127 @@ +#!/usr/bin/python +# Software License Agreement (BSD License) +# +# Copyright (c) 2013, Juergen Sturm, TUM +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of TUM nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +# Requirements: +# sudo apt-get install python-argparse + +""" +The Kinect provides the color and depth images in an un-synchronized way. This means that the set of time stamps from the color images do not intersect with those of the depth images. Therefore, we need some way of associating color images to depth images. + +For this purpose, you can use the ''associate.py'' script. It reads the time stamps from the rgb.txt file and the depth.txt file, and joins them by finding the best matches. +""" + +import argparse +import sys +import os +import numpy + + +def read_file_list(filename): + """ + Reads a trajectory from a text file. + + File format: + The file format is "stamp d1 d2 d3 ...", where stamp denotes the time stamp (to be matched) + and "d1 d2 d3.." is arbitary data (e.g., a 3D position and 3D orientation) associated to this timestamp. + + Input: + filename -- File name + + Output: + dict -- dictionary of (stamp,data) tuples + + """ + file = open(filename) + data = file.read() + lines = data.replace(","," ").replace("\t"," ").split("\n") + list = [[v.strip() for v in line.split(" ") if v.strip()!=""] for line in lines if len(line)>0 and line[0]!="#"] + list = [(float(l[0]),l[1:]) for l in list if len(l)>1] + return dict(list) + +def associate(first_list, second_list,offset,max_difference): + """ + Associate two dictionaries of (stamp,data). As the time stamps never match exactly, we aim + to find the closest match for every input tuple. + + Input: + first_list -- first dictionary of (stamp,data) tuples + second_list -- second dictionary of (stamp,data) tuples + offset -- time offset between both dictionaries (e.g., to model the delay between the sensors) + max_difference -- search radius for candidate generation + + Output: + matches -- list of matched tuples ((stamp1,data1),(stamp2,data2)) + + """ + first_keys = first_list.keys() + second_keys = second_list.keys() + potential_matches = [(abs(a - (b + offset)), a, b) + for a in first_keys + for b in second_keys + if abs(a - (b + offset)) < max_difference] + potential_matches.sort() + matches = [] + for diff, a, b in potential_matches: + if a in first_keys and b in second_keys: + first_keys.remove(a) + second_keys.remove(b) + matches.append((a, b)) + + matches.sort() + return matches + +if __name__ == '__main__': + + # parse command line + parser = argparse.ArgumentParser(description=''' + This script takes two data files with timestamps and associates them + ''') + parser.add_argument('first_file', help='first text file (format: timestamp data)') + parser.add_argument('second_file', help='second text file (format: timestamp data)') + parser.add_argument('--first_only', help='only output associated lines from first file', action='store_true') + parser.add_argument('--offset', help='time offset added to the timestamps of the second file (default: 0.0)',default=0.0) + parser.add_argument('--max_difference', help='maximally allowed time difference for matching entries (default: 0.02)',default=0.02) + args = parser.parse_args() + + first_list = read_file_list(args.first_file) + second_list = read_file_list(args.second_file) + + matches = associate(first_list, second_list,float(args.offset),float(args.max_difference)) + + if args.first_only: + for a,b in matches: + print("%f %s"%(a," ".join(first_list[a]))) + else: + for a,b in matches: + print("%f %s %f %s"%(a," ".join(first_list[a]),b-float(args.offset)," ".join(second_list[b]))) + diff --git a/vSLAM/ch8/data/associate.txt b/vSLAM/ch8/data/associate.txt new file mode 100644 index 00000000..ebe7df90 --- /dev/null +++ b/vSLAM/ch8/data/associate.txt @@ -0,0 +1,573 @@ +1305031453.359684 rgb/1305031453.359684.png 1305031453.374112 depth/1305031453.374112.png +1305031453.391690 rgb/1305031453.391690.png 1305031453.404816 depth/1305031453.404816.png +1305031453.423683 rgb/1305031453.423683.png 1305031453.436941 depth/1305031453.436941.png +1305031453.459685 rgb/1305031453.459685.png 1305031453.473352 depth/1305031453.473352.png +1305031453.491698 rgb/1305031453.491698.png 1305031453.505218 depth/1305031453.505218.png +1305031453.523684 rgb/1305031453.523684.png 1305031453.538301 depth/1305031453.538301.png +1305031453.559753 rgb/1305031453.559753.png 1305031453.574074 depth/1305031453.574074.png +1305031453.591640 rgb/1305031453.591640.png 1305031453.605314 depth/1305031453.605314.png +1305031453.627706 rgb/1305031453.627706.png 1305031453.636951 depth/1305031453.636951.png +1305031453.659600 rgb/1305031453.659600.png 1305031453.673185 depth/1305031453.673185.png +1305031453.691678 rgb/1305031453.691678.png 1305031453.705487 depth/1305031453.705487.png +1305031453.727652 rgb/1305031453.727652.png 1305031453.736856 depth/1305031453.736856.png +1305031453.759694 rgb/1305031453.759694.png 1305031453.773786 depth/1305031453.773786.png +1305031453.791716 rgb/1305031453.791716.png 1305031453.805041 depth/1305031453.805041.png +1305031453.827773 rgb/1305031453.827773.png 1305031453.840352 depth/1305031453.840352.png +1305031453.859705 rgb/1305031453.859705.png 1305031453.869618 depth/1305031453.869618.png +1305031453.891710 rgb/1305031453.891710.png 1305031453.905519 depth/1305031453.905519.png +1305031453.927723 rgb/1305031453.927723.png 1305031453.940012 depth/1305031453.940012.png +1305031453.959641 rgb/1305031453.959641.png 1305031453.972592 depth/1305031453.972592.png +1305031453.991624 rgb/1305031453.991624.png 1305031454.003179 depth/1305031454.003179.png +1305031454.027662 rgb/1305031454.027662.png 1305031454.040976 depth/1305031454.040976.png +1305031454.059654 rgb/1305031454.059654.png 1305031454.072690 depth/1305031454.072690.png +1305031454.091651 rgb/1305031454.091651.png 1305031454.104619 depth/1305031454.104619.png +1305031454.127701 rgb/1305031454.127701.png 1305031454.141030 depth/1305031454.141030.png +1305031454.159672 rgb/1305031454.159672.png 1305031454.172688 depth/1305031454.172688.png +1305031454.191658 rgb/1305031454.191658.png 1305031454.204626 depth/1305031454.204626.png +1305031454.227671 rgb/1305031454.227671.png 1305031454.240858 depth/1305031454.240858.png +1305031454.259627 rgb/1305031454.259627.png 1305031454.273489 depth/1305031454.273489.png +1305031454.291639 rgb/1305031454.291639.png 1305031454.304744 depth/1305031454.304744.png +1305031454.327699 rgb/1305031454.327699.png 1305031454.340806 depth/1305031454.340806.png +1305031454.359636 rgb/1305031454.359636.png 1305031454.372652 depth/1305031454.372652.png +1305031454.391677 rgb/1305031454.391677.png 1305031454.401962 depth/1305031454.401962.png +1305031454.427465 rgb/1305031454.427465.png 1305031454.437248 depth/1305031454.437248.png +1305031454.459913 rgb/1305031454.459913.png 1305031454.470741 depth/1305031454.470741.png +1305031454.491617 rgb/1305031454.491617.png 1305031454.503859 depth/1305031454.503859.png +1305031454.527700 rgb/1305031454.527700.png 1305031454.538424 depth/1305031454.538424.png +1305031454.559575 rgb/1305031454.559575.png 1305031454.570323 depth/1305031454.570323.png +1305031454.591635 rgb/1305031454.591635.png 1305031454.602019 depth/1305031454.602019.png +1305031454.627580 rgb/1305031454.627580.png 1305031454.639284 depth/1305031454.639284.png +1305031454.659528 rgb/1305031454.659528.png 1305031454.669573 depth/1305031454.669573.png +1305031454.691884 rgb/1305031454.691884.png 1305031454.702030 depth/1305031454.702030.png +1305031454.727659 rgb/1305031454.727659.png 1305031454.740764 depth/1305031454.740764.png +1305031454.759732 rgb/1305031454.759732.png 1305031454.772865 depth/1305031454.772865.png +1305031454.791641 rgb/1305031454.791641.png 1305031454.802574 depth/1305031454.802574.png +1305031454.827570 rgb/1305031454.827570.png 1305031454.840500 depth/1305031454.840500.png +1305031454.859620 rgb/1305031454.859620.png 1305031454.870269 depth/1305031454.870269.png +1305031454.891764 rgb/1305031454.891764.png 1305031454.901065 depth/1305031454.901065.png +1305031454.927567 rgb/1305031454.927567.png 1305031454.940240 depth/1305031454.940240.png +1305031454.959648 rgb/1305031454.959648.png 1305031454.973081 depth/1305031454.973081.png +1305031454.991937 rgb/1305031454.991937.png 1305031455.010759 depth/1305031455.010759.png +1305031455.027799 rgb/1305031455.027799.png 1305031455.040446 depth/1305031455.040446.png +1305031455.059636 rgb/1305031455.059636.png 1305031455.074282 depth/1305031455.074282.png +1305031455.091700 rgb/1305031455.091700.png 1305031455.110340 depth/1305031455.110340.png +1305031455.127695 rgb/1305031455.127695.png 1305031455.142700 depth/1305031455.142700.png +1305031455.159720 rgb/1305031455.159720.png 1305031455.172771 depth/1305031455.172771.png +1305031455.191655 rgb/1305031455.191655.png 1305031455.210307 depth/1305031455.210307.png +1305031455.227581 rgb/1305031455.227581.png 1305031455.240960 depth/1305031455.240960.png +1305031455.259631 rgb/1305031455.259631.png 1305031455.273001 depth/1305031455.273001.png +1305031455.291831 rgb/1305031455.291831.png 1305031455.310303 depth/1305031455.310303.png +1305031455.327766 rgb/1305031455.327766.png 1305031455.342381 depth/1305031455.342381.png +1305031455.359630 rgb/1305031455.359630.png 1305031455.374120 depth/1305031455.374120.png +1305031455.391665 rgb/1305031455.391665.png 1305031455.409213 depth/1305031455.409213.png +1305031455.427642 rgb/1305031455.427642.png 1305031455.442380 depth/1305031455.442380.png +1305031455.459589 rgb/1305031455.459589.png 1305031455.473168 depth/1305031455.473168.png +1305031455.491637 rgb/1305031455.491637.png 1305031455.509397 depth/1305031455.509397.png +1305031455.527610 rgb/1305031455.527610.png 1305031455.540835 depth/1305031455.540835.png +1305031455.559669 rgb/1305031455.559669.png 1305031455.572996 depth/1305031455.572996.png +1305031455.591645 rgb/1305031455.591645.png 1305031455.608802 depth/1305031455.608802.png +1305031455.627617 rgb/1305031455.627617.png 1305031455.641333 depth/1305031455.641333.png +1305031455.659615 rgb/1305031455.659615.png 1305031455.672887 depth/1305031455.672887.png +1305031455.691605 rgb/1305031455.691605.png 1305031455.707680 depth/1305031455.707680.png +1305031455.727628 rgb/1305031455.727628.png 1305031455.742005 depth/1305031455.742005.png +1305031455.759683 rgb/1305031455.759683.png 1305031455.773667 depth/1305031455.773667.png +1305031455.791666 rgb/1305031455.791666.png 1305031455.809109 depth/1305031455.809109.png +1305031455.827590 rgb/1305031455.827590.png 1305031455.838364 depth/1305031455.838364.png +1305031455.859526 rgb/1305031455.859526.png 1305031455.872220 depth/1305031455.872220.png +1305031455.891657 rgb/1305031455.891657.png 1305031455.908418 depth/1305031455.908418.png +1305031455.927955 rgb/1305031455.927955.png 1305031455.939606 depth/1305031455.939606.png +1305031455.959716 rgb/1305031455.959716.png 1305031455.973594 depth/1305031455.973594.png +1305031455.991694 rgb/1305031455.991694.png 1305031456.008998 depth/1305031456.008998.png +1305031456.027770 rgb/1305031456.027770.png 1305031456.041930 depth/1305031456.041930.png +1305031456.059713 rgb/1305031456.059713.png 1305031456.073846 depth/1305031456.073846.png +1305031456.091707 rgb/1305031456.091707.png 1305031456.108963 depth/1305031456.108963.png +1305031456.127645 rgb/1305031456.127645.png 1305031456.140836 depth/1305031456.140836.png +1305031456.159731 rgb/1305031456.159731.png 1305031456.173198 depth/1305031456.173198.png +1305031456.191658 rgb/1305031456.191658.png 1305031456.208934 depth/1305031456.208934.png +1305031456.227678 rgb/1305031456.227678.png 1305031456.240996 depth/1305031456.240996.png +1305031456.291675 rgb/1305031456.291675.png 1305031456.277928 depth/1305031456.277928.png +1305031456.327718 rgb/1305031456.327718.png 1305031456.341659 depth/1305031456.341659.png +1305031456.391619 rgb/1305031456.391619.png 1305031456.377115 depth/1305031456.377115.png +1305031456.427662 rgb/1305031456.427662.png 1305031456.440717 depth/1305031456.440717.png +1305031456.491677 rgb/1305031456.491677.png 1305031456.476027 depth/1305031456.476027.png +1305031456.527641 rgb/1305031456.527641.png 1305031456.541832 depth/1305031456.541832.png +1305031456.591651 rgb/1305031456.591651.png 1305031456.576087 depth/1305031456.576087.png +1305031456.627612 rgb/1305031456.627612.png 1305031456.640699 depth/1305031456.640699.png +1305031456.691612 rgb/1305031456.691612.png 1305031456.675835 depth/1305031456.675835.png +1305031456.727693 rgb/1305031456.727693.png 1305031456.740863 depth/1305031456.740863.png +1305031456.791649 rgb/1305031456.791649.png 1305031456.777218 depth/1305031456.777218.png +1305031456.827603 rgb/1305031456.827603.png 1305031456.841050 depth/1305031456.841050.png +1305031456.891672 rgb/1305031456.891672.png 1305031456.878006 depth/1305031456.878006.png +1305031456.927690 rgb/1305031456.927690.png 1305031456.942298 depth/1305031456.942298.png +1305031456.959667 rgb/1305031456.959667.png 1305031456.977139 depth/1305031456.977139.png +1305031456.991709 rgb/1305031456.991709.png 1305031457.006193 depth/1305031457.006193.png +1305031457.027648 rgb/1305031457.027648.png 1305031457.042512 depth/1305031457.042512.png +1305031457.091655 rgb/1305031457.091655.png 1305031457.076011 depth/1305031457.076011.png +1305031457.127632 rgb/1305031457.127632.png 1305031457.142120 depth/1305031457.142120.png +1305031457.191735 rgb/1305031457.191735.png 1305031457.177463 depth/1305031457.177463.png +1305031457.227543 rgb/1305031457.227543.png 1305031457.240792 depth/1305031457.240792.png +1305031457.291656 rgb/1305031457.291656.png 1305031457.277247 depth/1305031457.277247.png +1305031457.327548 rgb/1305031457.327548.png 1305031457.342954 depth/1305031457.342954.png +1305031457.391684 rgb/1305031457.391684.png 1305031457.376037 depth/1305031457.376037.png +1305031457.427641 rgb/1305031457.427641.png 1305031457.441357 depth/1305031457.441357.png +1305031457.491705 rgb/1305031457.491705.png 1305031457.476577 depth/1305031457.476577.png +1305031457.527638 rgb/1305031457.527638.png 1305031457.508603 depth/1305031457.508603.png +1305031457.559685 rgb/1305031457.559685.png 1305031457.543946 depth/1305031457.543946.png +1305031457.591678 rgb/1305031457.591678.png 1305031457.576581 depth/1305031457.576581.png +1305031457.627526 rgb/1305031457.627526.png 1305031457.643534 depth/1305031457.643534.png +1305031457.659632 rgb/1305031457.659632.png 1305031457.675414 depth/1305031457.675414.png +1305031457.691570 rgb/1305031457.691570.png 1305031457.707739 depth/1305031457.707739.png +1305031457.727669 rgb/1305031457.727669.png 1305031457.745071 depth/1305031457.745071.png +1305031457.759556 rgb/1305031457.759556.png 1305031457.773518 depth/1305031457.773518.png +1305031457.791567 rgb/1305031457.791567.png 1305031457.807824 depth/1305031457.807824.png +1305031457.827699 rgb/1305031457.827699.png 1305031457.842853 depth/1305031457.842853.png +1305031457.859623 rgb/1305031457.859623.png 1305031457.875920 depth/1305031457.875920.png +1305031457.891593 rgb/1305031457.891593.png 1305031457.906126 depth/1305031457.906126.png +1305031457.927633 rgb/1305031457.927633.png 1305031457.942604 depth/1305031457.942604.png +1305031457.991644 rgb/1305031457.991644.png 1305031457.976744 depth/1305031457.976744.png +1305031458.027845 rgb/1305031458.027845.png 1305031458.009019 depth/1305031458.009019.png +1305031458.059689 rgb/1305031458.059689.png 1305031458.046303 depth/1305031458.046303.png +1305031458.091690 rgb/1305031458.091690.png 1305031458.077315 depth/1305031458.077315.png +1305031458.127605 rgb/1305031458.127605.png 1305031458.108896 depth/1305031458.108896.png +1305031458.159638 rgb/1305031458.159638.png 1305031458.144808 depth/1305031458.144808.png +1305031458.191646 rgb/1305031458.191646.png 1305031458.178039 depth/1305031458.178039.png +1305031458.227611 rgb/1305031458.227611.png 1305031458.209384 depth/1305031458.209384.png +1305031458.259934 rgb/1305031458.259934.png 1305031458.245729 depth/1305031458.245729.png +1305031458.291664 rgb/1305031458.291664.png 1305031458.277447 depth/1305031458.277447.png +1305031458.327628 rgb/1305031458.327628.png 1305031458.308343 depth/1305031458.308343.png +1305031458.359590 rgb/1305031458.359590.png 1305031458.343898 depth/1305031458.343898.png +1305031458.391626 rgb/1305031458.391626.png 1305031458.376213 depth/1305031458.376213.png +1305031458.427598 rgb/1305031458.427598.png 1305031458.407856 depth/1305031458.407856.png +1305031458.459637 rgb/1305031458.459637.png 1305031458.443957 depth/1305031458.443957.png +1305031458.491696 rgb/1305031458.491696.png 1305031458.476034 depth/1305031458.476034.png +1305031458.527737 rgb/1305031458.527737.png 1305031458.508869 depth/1305031458.508869.png +1305031458.559628 rgb/1305031458.559628.png 1305031458.544401 depth/1305031458.544401.png +1305031458.591641 rgb/1305031458.591641.png 1305031458.576178 depth/1305031458.576178.png +1305031458.627659 rgb/1305031458.627659.png 1305031458.608421 depth/1305031458.608421.png +1305031458.659623 rgb/1305031458.659623.png 1305031458.643659 depth/1305031458.643659.png +1305031458.691674 rgb/1305031458.691674.png 1305031458.676991 depth/1305031458.676991.png +1305031458.727650 rgb/1305031458.727650.png 1305031458.744924 depth/1305031458.744924.png +1305031458.759945 rgb/1305031458.759945.png 1305031458.773802 depth/1305031458.773802.png +1305031458.791632 rgb/1305031458.791632.png 1305031458.810621 depth/1305031458.810621.png +1305031458.827564 rgb/1305031458.827564.png 1305031458.842919 depth/1305031458.842919.png +1305031458.891665 rgb/1305031458.891665.png 1305031458.875889 depth/1305031458.875889.png +1305031458.927621 rgb/1305031458.927621.png 1305031458.910599 depth/1305031458.910599.png +1305031458.959617 rgb/1305031458.959617.png 1305031458.943997 depth/1305031458.943997.png +1305031458.991647 rgb/1305031458.991647.png 1305031458.976007 depth/1305031458.976007.png +1305031459.027665 rgb/1305031459.027665.png 1305031459.012560 depth/1305031459.012560.png +1305031459.059631 rgb/1305031459.059631.png 1305031459.073657 depth/1305031459.073657.png +1305031459.127618 rgb/1305031459.127618.png 1305031459.112711 depth/1305031459.112711.png +1305031459.159639 rgb/1305031459.159639.png 1305031459.144497 depth/1305031459.144497.png +1305031459.191674 rgb/1305031459.191674.png 1305031459.176463 depth/1305031459.176463.png +1305031459.227607 rgb/1305031459.227607.png 1305031459.244159 depth/1305031459.244159.png +1305031459.259760 rgb/1305031459.259760.png 1305031459.274941 depth/1305031459.274941.png +1305031459.327632 rgb/1305031459.327632.png 1305031459.311921 depth/1305031459.311921.png +1305031459.359651 rgb/1305031459.359651.png 1305031459.374084 depth/1305031459.374084.png +1305031459.391667 rgb/1305031459.391667.png 1305031459.408831 depth/1305031459.408831.png +1305031459.427646 rgb/1305031459.427646.png 1305031459.443181 depth/1305031459.443181.png +1305031459.459679 rgb/1305031459.459679.png 1305031459.473401 depth/1305031459.473401.png +1305031459.527594 rgb/1305031459.527594.png 1305031459.510267 depth/1305031459.510267.png +1305031459.559647 rgb/1305031459.559647.png 1305031459.544431 depth/1305031459.544431.png +1305031459.591695 rgb/1305031459.591695.png 1305031459.576817 depth/1305031459.576817.png +1305031459.627608 rgb/1305031459.627608.png 1305031459.611939 depth/1305031459.611939.png +1305031459.659641 rgb/1305031459.659641.png 1305031459.643453 depth/1305031459.643453.png +1305031459.691604 rgb/1305031459.691604.png 1305031459.675678 depth/1305031459.675678.png +1305031459.727551 rgb/1305031459.727551.png 1305031459.743425 depth/1305031459.743425.png +1305031459.791650 rgb/1305031459.791650.png 1305031459.776577 depth/1305031459.776577.png +1305031459.827664 rgb/1305031459.827664.png 1305031459.812562 depth/1305031459.812562.png +1305031459.859660 rgb/1305031459.859660.png 1305031459.844736 depth/1305031459.844736.png +1305031459.891596 rgb/1305031459.891596.png 1305031459.877006 depth/1305031459.877006.png +1305031459.927607 rgb/1305031459.927607.png 1305031459.943616 depth/1305031459.943616.png +1305031459.991725 rgb/1305031459.991725.png 1305031459.979430 depth/1305031459.979430.png +1305031460.027565 rgb/1305031460.027565.png 1305031460.011909 depth/1305031460.011909.png +1305031460.059659 rgb/1305031460.059659.png 1305031460.043717 depth/1305031460.043717.png +1305031460.091717 rgb/1305031460.091717.png 1305031460.079449 depth/1305031460.079449.png +1305031460.127690 rgb/1305031460.127690.png 1305031460.111951 depth/1305031460.111951.png +1305031460.159678 rgb/1305031460.159678.png 1305031460.144204 depth/1305031460.144204.png +1305031460.191559 rgb/1305031460.191559.png 1305031460.178730 depth/1305031460.178730.png +1305031460.227761 rgb/1305031460.227761.png 1305031460.243467 depth/1305031460.243467.png +1305031460.291689 rgb/1305031460.291689.png 1305031460.279164 depth/1305031460.279164.png +1305031460.327512 rgb/1305031460.327512.png 1305031460.342879 depth/1305031460.342879.png +1305031460.391611 rgb/1305031460.391611.png 1305031460.377806 depth/1305031460.377806.png +1305031460.427477 rgb/1305031460.427477.png 1305031460.409883 depth/1305031460.409883.png +1305031460.459620 rgb/1305031460.459620.png 1305031460.444036 depth/1305031460.444036.png +1305031460.491504 rgb/1305031460.491504.png 1305031460.479856 depth/1305031460.479856.png +1305031460.527570 rgb/1305031460.527570.png 1305031460.508966 depth/1305031460.508966.png +1305031460.559647 rgb/1305031460.559647.png 1305031460.544245 depth/1305031460.544245.png +1305031460.591855 rgb/1305031460.591855.png 1305031460.579561 depth/1305031460.579561.png +1305031460.627625 rgb/1305031460.627625.png 1305031460.612190 depth/1305031460.612190.png +1305031460.659764 rgb/1305031460.659764.png 1305031460.644011 depth/1305031460.644011.png +1305031460.691671 rgb/1305031460.691671.png 1305031460.679350 depth/1305031460.679350.png +1305031460.727675 rgb/1305031460.727675.png 1305031460.711684 depth/1305031460.711684.png +1305031460.759667 rgb/1305031460.759667.png 1305031460.743767 depth/1305031460.743767.png +1305031460.791660 rgb/1305031460.791660.png 1305031460.779201 depth/1305031460.779201.png +1305031460.827660 rgb/1305031460.827660.png 1305031460.811318 depth/1305031460.811318.png +1305031460.859714 rgb/1305031460.859714.png 1305031460.843836 depth/1305031460.843836.png +1305031460.891774 rgb/1305031460.891774.png 1305031460.879093 depth/1305031460.879093.png +1305031460.927562 rgb/1305031460.927562.png 1305031460.943375 depth/1305031460.943375.png +1305031460.991668 rgb/1305031460.991668.png 1305031460.979083 depth/1305031460.979083.png +1305031461.027620 rgb/1305031461.027620.png 1305031461.043398 depth/1305031461.043398.png +1305031461.091728 rgb/1305031461.091728.png 1305031461.079602 depth/1305031461.079602.png +1305031461.127586 rgb/1305031461.127586.png 1305031461.111961 depth/1305031461.111961.png +1305031461.159720 rgb/1305031461.159720.png 1305031461.144098 depth/1305031461.144098.png +1305031461.192013 rgb/1305031461.192013.png 1305031461.179883 depth/1305031461.179883.png +1305031461.227607 rgb/1305031461.227607.png 1305031461.211180 depth/1305031461.211180.png +1305031461.259642 rgb/1305031461.259642.png 1305031461.246864 depth/1305031461.246864.png +1305031461.291656 rgb/1305031461.291656.png 1305031461.278888 depth/1305031461.278888.png +1305031461.327751 rgb/1305031461.327751.png 1305031461.311240 depth/1305031461.311240.png +1305031461.359709 rgb/1305031461.359709.png 1305031461.346875 depth/1305031461.346875.png +1305031461.391708 rgb/1305031461.391708.png 1305031461.378850 depth/1305031461.378850.png +1305031461.427624 rgb/1305031461.427624.png 1305031461.411130 depth/1305031461.411130.png +1305031461.459781 rgb/1305031461.459781.png 1305031461.447015 depth/1305031461.447015.png +1305031461.491677 rgb/1305031461.491677.png 1305031461.478901 depth/1305031461.478901.png +1305031461.527705 rgb/1305031461.527705.png 1305031461.512120 depth/1305031461.512120.png +1305031461.559677 rgb/1305031461.559677.png 1305031461.547338 depth/1305031461.547338.png +1305031461.591690 rgb/1305031461.591690.png 1305031461.578847 depth/1305031461.578847.png +1305031461.627541 rgb/1305031461.627541.png 1305031461.609662 depth/1305031461.609662.png +1305031461.659622 rgb/1305031461.659622.png 1305031461.646970 depth/1305031461.646970.png +1305031461.691563 rgb/1305031461.691563.png 1305031461.676203 depth/1305031461.676203.png +1305031461.727602 rgb/1305031461.727602.png 1305031461.711212 depth/1305031461.711212.png +1305031461.759684 rgb/1305031461.759684.png 1305031461.746919 depth/1305031461.746919.png +1305031461.791612 rgb/1305031461.791612.png 1305031461.778616 depth/1305031461.778616.png +1305031461.827615 rgb/1305031461.827615.png 1305031461.811319 depth/1305031461.811319.png +1305031461.859767 rgb/1305031461.859767.png 1305031461.847090 depth/1305031461.847090.png +1305031461.891723 rgb/1305031461.891723.png 1305031461.879162 depth/1305031461.879162.png +1305031461.927758 rgb/1305031461.927758.png 1305031461.911121 depth/1305031461.911121.png +1305031461.959703 rgb/1305031461.959703.png 1305031461.947264 depth/1305031461.947264.png +1305031461.991590 rgb/1305031461.991590.png 1305031461.979223 depth/1305031461.979223.png +1305031462.027675 rgb/1305031462.027675.png 1305031462.011791 depth/1305031462.011791.png +1305031462.059837 rgb/1305031462.059837.png 1305031462.047463 depth/1305031462.047463.png +1305031462.091777 rgb/1305031462.091777.png 1305031462.079285 depth/1305031462.079285.png +1305031462.127739 rgb/1305031462.127739.png 1305031462.112081 depth/1305031462.112081.png +1305031462.159646 rgb/1305031462.159646.png 1305031462.147634 depth/1305031462.147634.png +1305031462.191641 rgb/1305031462.191641.png 1305031462.179358 depth/1305031462.179358.png +1305031462.227633 rgb/1305031462.227633.png 1305031462.212836 depth/1305031462.212836.png +1305031462.259765 rgb/1305031462.259765.png 1305031462.248986 depth/1305031462.248986.png +1305031462.291629 rgb/1305031462.291629.png 1305031462.280774 depth/1305031462.280774.png +1305031462.327540 rgb/1305031462.327540.png 1305031462.311931 depth/1305031462.311931.png +1305031462.359732 rgb/1305031462.359732.png 1305031462.347816 depth/1305031462.347816.png +1305031462.391695 rgb/1305031462.391695.png 1305031462.379950 depth/1305031462.379950.png +1305031462.427635 rgb/1305031462.427635.png 1305031462.413016 depth/1305031462.413016.png +1305031462.459897 rgb/1305031462.459897.png 1305031462.448295 depth/1305031462.448295.png +1305031462.492008 rgb/1305031462.492008.png 1305031462.480843 depth/1305031462.480843.png +1305031462.527670 rgb/1305031462.527670.png 1305031462.517041 depth/1305031462.517041.png +1305031462.559862 rgb/1305031462.559862.png 1305031462.548959 depth/1305031462.548959.png +1305031462.591862 rgb/1305031462.591862.png 1305031462.581088 depth/1305031462.581088.png +1305031462.627851 rgb/1305031462.627851.png 1305031462.617123 depth/1305031462.617123.png +1305031462.659660 rgb/1305031462.659660.png 1305031462.648708 depth/1305031462.648708.png +1305031462.692548 rgb/1305031462.692548.png 1305031462.680788 depth/1305031462.680788.png +1305031462.727652 rgb/1305031462.727652.png 1305031462.716812 depth/1305031462.716812.png +1305031462.759782 rgb/1305031462.759782.png 1305031462.748732 depth/1305031462.748732.png +1305031462.791943 rgb/1305031462.791943.png 1305031462.780885 depth/1305031462.780885.png +1305031462.827816 rgb/1305031462.827816.png 1305031462.816821 depth/1305031462.816821.png +1305031462.859782 rgb/1305031462.859782.png 1305031462.848525 depth/1305031462.848525.png +1305031462.891847 rgb/1305031462.891847.png 1305031462.880471 depth/1305031462.880471.png +1305031462.927607 rgb/1305031462.927607.png 1305031462.916800 depth/1305031462.916800.png +1305031462.959676 rgb/1305031462.959676.png 1305031462.947939 depth/1305031462.947939.png +1305031462.995550 rgb/1305031462.995550.png 1305031462.979943 depth/1305031462.979943.png +1305031463.027667 rgb/1305031463.027667.png 1305031463.016121 depth/1305031463.016121.png +1305031463.059810 rgb/1305031463.059810.png 1305031463.050783 depth/1305031463.050783.png +1305031463.095809 rgb/1305031463.095809.png 1305031463.076870 depth/1305031463.076870.png +1305031463.127550 rgb/1305031463.127550.png 1305031463.116806 depth/1305031463.116806.png +1305031463.159787 rgb/1305031463.159787.png 1305031463.148565 depth/1305031463.148565.png +1305031463.195657 rgb/1305031463.195657.png 1305031463.180505 depth/1305031463.180505.png +1305031463.227784 rgb/1305031463.227784.png 1305031463.217123 depth/1305031463.217123.png +1305031463.260034 rgb/1305031463.260034.png 1305031463.248719 depth/1305031463.248719.png +1305031463.295737 rgb/1305031463.295737.png 1305031463.278737 depth/1305031463.278737.png +1305031463.327739 rgb/1305031463.327739.png 1305031463.317110 depth/1305031463.317110.png +1305031463.359750 rgb/1305031463.359750.png 1305031463.348740 depth/1305031463.348740.png +1305031463.395630 rgb/1305031463.395630.png 1305031463.380514 depth/1305031463.380514.png +1305031463.427716 rgb/1305031463.427716.png 1305031463.416326 depth/1305031463.416326.png +1305031463.459756 rgb/1305031463.459756.png 1305031463.444773 depth/1305031463.444773.png +1305031463.495629 rgb/1305031463.495629.png 1305031463.480415 depth/1305031463.480415.png +1305031463.527670 rgb/1305031463.527670.png 1305031463.516994 depth/1305031463.516994.png +1305031463.559751 rgb/1305031463.559751.png 1305031463.548505 depth/1305031463.548505.png +1305031463.595600 rgb/1305031463.595600.png 1305031463.580684 depth/1305031463.580684.png +1305031463.627588 rgb/1305031463.627588.png 1305031463.616671 depth/1305031463.616671.png +1305031463.659766 rgb/1305031463.659766.png 1305031463.646147 depth/1305031463.646147.png +1305031463.695640 rgb/1305031463.695640.png 1305031463.683908 depth/1305031463.683908.png +1305031463.727588 rgb/1305031463.727588.png 1305031463.716110 depth/1305031463.716110.png +1305031463.759674 rgb/1305031463.759674.png 1305031463.747849 depth/1305031463.747849.png +1305031463.795647 rgb/1305031463.795647.png 1305031463.783912 depth/1305031463.783912.png +1305031463.827761 rgb/1305031463.827761.png 1305031463.815883 depth/1305031463.815883.png +1305031463.859910 rgb/1305031463.859910.png 1305031463.848094 depth/1305031463.848094.png +1305031463.895648 rgb/1305031463.895648.png 1305031463.883817 depth/1305031463.883817.png +1305031463.927664 rgb/1305031463.927664.png 1305031463.917433 depth/1305031463.917433.png +1305031463.959680 rgb/1305031463.959680.png 1305031463.944435 depth/1305031463.944435.png +1305031463.995821 rgb/1305031463.995821.png 1305031463.983748 depth/1305031463.983748.png +1305031464.027703 rgb/1305031464.027703.png 1305031464.015867 depth/1305031464.015867.png +1305031464.059652 rgb/1305031464.059652.png 1305031464.047778 depth/1305031464.047778.png +1305031464.095634 rgb/1305031464.095634.png 1305031464.083152 depth/1305031464.083152.png +1305031464.127681 rgb/1305031464.127681.png 1305031464.115837 depth/1305031464.115837.png +1305031464.159817 rgb/1305031464.159817.png 1305031464.147663 depth/1305031464.147663.png +1305031464.195585 rgb/1305031464.195585.png 1305031464.183566 depth/1305031464.183566.png +1305031464.227624 rgb/1305031464.227624.png 1305031464.212447 depth/1305031464.212447.png +1305031464.259644 rgb/1305031464.259644.png 1305031464.247602 depth/1305031464.247602.png +1305031464.295667 rgb/1305031464.295667.png 1305031464.283694 depth/1305031464.283694.png +1305031464.327866 rgb/1305031464.327866.png 1305031464.315699 depth/1305031464.315699.png +1305031464.359684 rgb/1305031464.359684.png 1305031464.347553 depth/1305031464.347553.png +1305031464.395611 rgb/1305031464.395611.png 1305031464.383465 depth/1305031464.383465.png +1305031464.427634 rgb/1305031464.427634.png 1305031464.415539 depth/1305031464.415539.png +1305031464.459689 rgb/1305031464.459689.png 1305031464.444269 depth/1305031464.444269.png +1305031464.495633 rgb/1305031464.495633.png 1305031464.487561 depth/1305031464.487561.png +1305031464.527574 rgb/1305031464.527574.png 1305031464.513688 depth/1305031464.513688.png +1305031464.559703 rgb/1305031464.559703.png 1305031464.548007 depth/1305031464.548007.png +1305031464.595698 rgb/1305031464.595698.png 1305031464.584260 depth/1305031464.584260.png +1305031464.627672 rgb/1305031464.627672.png 1305031464.615688 depth/1305031464.615688.png +1305031464.659749 rgb/1305031464.659749.png 1305031464.648851 depth/1305031464.648851.png +1305031464.695663 rgb/1305031464.695663.png 1305031464.684318 depth/1305031464.684318.png +1305031464.727652 rgb/1305031464.727652.png 1305031464.716305 depth/1305031464.716305.png +1305031464.759740 rgb/1305031464.759740.png 1305031464.748588 depth/1305031464.748588.png +1305031464.796021 rgb/1305031464.796021.png 1305031464.784268 depth/1305031464.784268.png +1305031464.827759 rgb/1305031464.827759.png 1305031464.816195 depth/1305031464.816195.png +1305031464.859654 rgb/1305031464.859654.png 1305031464.848283 depth/1305031464.848283.png +1305031464.895817 rgb/1305031464.895817.png 1305031464.884177 depth/1305031464.884177.png +1305031464.927799 rgb/1305031464.927799.png 1305031464.916391 depth/1305031464.916391.png +1305031464.959763 rgb/1305031464.959763.png 1305031464.952471 depth/1305031464.952471.png +1305031464.995687 rgb/1305031464.995687.png 1305031464.984257 depth/1305031464.984257.png +1305031465.027823 rgb/1305031465.027823.png 1305031465.015390 depth/1305031465.015390.png +1305031465.059749 rgb/1305031465.059749.png 1305031465.048430 depth/1305031465.048430.png +1305031465.095700 rgb/1305031465.095700.png 1305031465.083338 depth/1305031465.083338.png +1305031465.127664 rgb/1305031465.127664.png 1305031465.115475 depth/1305031465.115475.png +1305031465.159842 rgb/1305031465.159842.png 1305031465.151558 depth/1305031465.151558.png +1305031465.195564 rgb/1305031465.195564.png 1305031465.183558 depth/1305031465.183558.png +1305031465.227907 rgb/1305031465.227907.png 1305031465.215832 depth/1305031465.215832.png +1305031465.259807 rgb/1305031465.259807.png 1305031465.251788 depth/1305031465.251788.png +1305031465.295623 rgb/1305031465.295623.png 1305031465.283737 depth/1305031465.283737.png +1305031465.327674 rgb/1305031465.327674.png 1305031465.315985 depth/1305031465.315985.png +1305031465.359948 rgb/1305031465.359948.png 1305031465.351729 depth/1305031465.351729.png +1305031465.395586 rgb/1305031465.395586.png 1305031465.383701 depth/1305031465.383701.png +1305031465.427697 rgb/1305031465.427697.png 1305031465.416543 depth/1305031465.416543.png +1305031465.460125 rgb/1305031465.460125.png 1305031465.452401 depth/1305031465.452401.png +1305031465.495703 rgb/1305031465.495703.png 1305031465.483803 depth/1305031465.483803.png +1305031465.527622 rgb/1305031465.527622.png 1305031465.516043 depth/1305031465.516043.png +1305031465.559812 rgb/1305031465.559812.png 1305031465.551838 depth/1305031465.551838.png +1305031465.595599 rgb/1305031465.595599.png 1305031465.583570 depth/1305031465.583570.png +1305031465.627688 rgb/1305031465.627688.png 1305031465.615685 depth/1305031465.615685.png +1305031465.660060 rgb/1305031465.660060.png 1305031465.651645 depth/1305031465.651645.png +1305031465.695668 rgb/1305031465.695668.png 1305031465.684759 depth/1305031465.684759.png +1305031465.727682 rgb/1305031465.727682.png 1305031465.716279 depth/1305031465.716279.png +1305031465.759766 rgb/1305031465.759766.png 1305031465.753153 depth/1305031465.753153.png +1305031465.795937 rgb/1305031465.795937.png 1305031465.784387 depth/1305031465.784387.png +1305031465.827996 rgb/1305031465.827996.png 1305031465.816591 depth/1305031465.816591.png +1305031465.859861 rgb/1305031465.859861.png 1305031465.852860 depth/1305031465.852860.png +1305031465.895494 rgb/1305031465.895494.png 1305031465.884370 depth/1305031465.884370.png +1305031465.927495 rgb/1305031465.927495.png 1305031465.912828 depth/1305031465.912828.png +1305031465.959710 rgb/1305031465.959710.png 1305031465.952840 depth/1305031465.952840.png +1305031465.995753 rgb/1305031465.995753.png 1305031465.984183 depth/1305031465.984183.png +1305031466.027644 rgb/1305031466.027644.png 1305031466.016599 depth/1305031466.016599.png +1305031466.059757 rgb/1305031466.059757.png 1305031466.052655 depth/1305031466.052655.png +1305031466.095840 rgb/1305031466.095840.png 1305031466.083913 depth/1305031466.083913.png +1305031466.127640 rgb/1305031466.127640.png 1305031466.116400 depth/1305031466.116400.png +1305031466.160428 rgb/1305031466.160428.png 1305031466.152540 depth/1305031466.152540.png +1305031466.195833 rgb/1305031466.195833.png 1305031466.184186 depth/1305031466.184186.png +1305031466.227951 rgb/1305031466.227951.png 1305031466.220477 depth/1305031466.220477.png +1305031466.259815 rgb/1305031466.259815.png 1305031466.252491 depth/1305031466.252491.png +1305031466.295737 rgb/1305031466.295737.png 1305031466.284389 depth/1305031466.284389.png +1305031466.327702 rgb/1305031466.327702.png 1305031466.320055 depth/1305031466.320055.png +1305031466.359829 rgb/1305031466.359829.png 1305031466.352082 depth/1305031466.352082.png +1305031466.395784 rgb/1305031466.395784.png 1305031466.384479 depth/1305031466.384479.png +1305031466.427819 rgb/1305031466.427819.png 1305031466.420844 depth/1305031466.420844.png +1305031466.459790 rgb/1305031466.459790.png 1305031466.452369 depth/1305031466.452369.png +1305031466.495809 rgb/1305031466.495809.png 1305031466.483315 depth/1305031466.483315.png +1305031466.527538 rgb/1305031466.527538.png 1305031466.519548 depth/1305031466.519548.png +1305031466.560353 rgb/1305031466.560353.png 1305031466.552219 depth/1305031466.552219.png +1305031466.595936 rgb/1305031466.595936.png 1305031466.584438 depth/1305031466.584438.png +1305031466.627549 rgb/1305031466.627549.png 1305031466.620424 depth/1305031466.620424.png +1305031466.659688 rgb/1305031466.659688.png 1305031466.648654 depth/1305031466.648654.png +1305031466.695822 rgb/1305031466.695822.png 1305031466.684412 depth/1305031466.684412.png +1305031466.728074 rgb/1305031466.728074.png 1305031466.719744 depth/1305031466.719744.png +1305031466.759637 rgb/1305031466.759637.png 1305031466.748734 depth/1305031466.748734.png +1305031466.795604 rgb/1305031466.795604.png 1305031466.784300 depth/1305031466.784300.png +1305031466.827879 rgb/1305031466.827879.png 1305031466.819502 depth/1305031466.819502.png +1305031466.859665 rgb/1305031466.859665.png 1305031466.851527 depth/1305031466.851527.png +1305031466.895694 rgb/1305031466.895694.png 1305031466.883430 depth/1305031466.883430.png +1305031466.927756 rgb/1305031466.927756.png 1305031466.919411 depth/1305031466.919411.png +1305031466.959728 rgb/1305031466.959728.png 1305031466.952451 depth/1305031466.952451.png +1305031466.995712 rgb/1305031466.995712.png 1305031466.984027 depth/1305031466.984027.png +1305031467.027843 rgb/1305031467.027843.png 1305031467.020424 depth/1305031467.020424.png +1305031467.059700 rgb/1305031467.059700.png 1305031467.052391 depth/1305031467.052391.png +1305031467.095687 rgb/1305031467.095687.png 1305031467.084130 depth/1305031467.084130.png +1305031467.128974 rgb/1305031467.128974.png 1305031467.120528 depth/1305031467.120528.png +1305031467.159660 rgb/1305031467.159660.png 1305031467.152363 depth/1305031467.152363.png +1305031467.195663 rgb/1305031467.195663.png 1305031467.184216 depth/1305031467.184216.png +1305031467.227704 rgb/1305031467.227704.png 1305031467.220466 depth/1305031467.220466.png +1305031467.259694 rgb/1305031467.259694.png 1305031467.252275 depth/1305031467.252275.png +1305031467.295846 rgb/1305031467.295846.png 1305031467.284258 depth/1305031467.284258.png +1305031467.328008 rgb/1305031467.328008.png 1305031467.318028 depth/1305031467.318028.png +1305031467.359654 rgb/1305031467.359654.png 1305031467.349355 depth/1305031467.349355.png +1305031467.395756 rgb/1305031467.395756.png 1305031467.383844 depth/1305031467.383844.png +1305031467.427783 rgb/1305031467.427783.png 1305031467.420160 depth/1305031467.420160.png +1305031467.459692 rgb/1305031467.459692.png 1305031467.452057 depth/1305031467.452057.png +1305031467.496058 rgb/1305031467.496058.png 1305031467.484357 depth/1305031467.484357.png +1305031467.527663 rgb/1305031467.527663.png 1305031467.520535 depth/1305031467.520535.png +1305031467.559763 rgb/1305031467.559763.png 1305031467.552164 depth/1305031467.552164.png +1305031467.595989 rgb/1305031467.595989.png 1305031467.584354 depth/1305031467.584354.png +1305031467.627532 rgb/1305031467.627532.png 1305031467.618680 depth/1305031467.618680.png +1305031467.659626 rgb/1305031467.659626.png 1305031467.651977 depth/1305031467.651977.png +1305031467.695886 rgb/1305031467.695886.png 1305031467.686044 depth/1305031467.686044.png +1305031467.727535 rgb/1305031467.727535.png 1305031467.718326 depth/1305031467.718326.png +1305031467.759907 rgb/1305031467.759907.png 1305031467.752580 depth/1305031467.752580.png +1305031467.796075 rgb/1305031467.796075.png 1305031467.788562 depth/1305031467.788562.png +1305031467.827800 rgb/1305031467.827800.png 1305031467.820454 depth/1305031467.820454.png +1305031467.859729 rgb/1305031467.859729.png 1305031467.852678 depth/1305031467.852678.png +1305031467.895947 rgb/1305031467.895947.png 1305031467.888472 depth/1305031467.888472.png +1305031467.927754 rgb/1305031467.927754.png 1305031467.920800 depth/1305031467.920800.png +1305031467.959826 rgb/1305031467.959826.png 1305031467.952485 depth/1305031467.952485.png +1305031467.995754 rgb/1305031467.995754.png 1305031467.988523 depth/1305031467.988523.png +1305031468.028107 rgb/1305031468.028107.png 1305031468.020491 depth/1305031468.020491.png +1305031468.059850 rgb/1305031468.059850.png 1305031468.052668 depth/1305031468.052668.png +1305031468.095867 rgb/1305031468.095867.png 1305031468.088379 depth/1305031468.088379.png +1305031468.127816 rgb/1305031468.127816.png 1305031468.120522 depth/1305031468.120522.png +1305031468.159864 rgb/1305031468.159864.png 1305031468.152356 depth/1305031468.152356.png +1305031468.195985 rgb/1305031468.195985.png 1305031468.188327 depth/1305031468.188327.png +1305031468.228158 rgb/1305031468.228158.png 1305031468.220648 depth/1305031468.220648.png +1305031468.259754 rgb/1305031468.259754.png 1305031468.252517 depth/1305031468.252517.png +1305031468.295830 rgb/1305031468.295830.png 1305031468.288361 depth/1305031468.288361.png +1305031468.327847 rgb/1305031468.327847.png 1305031468.320522 depth/1305031468.320522.png +1305031468.359787 rgb/1305031468.359787.png 1305031468.352594 depth/1305031468.352594.png +1305031468.395860 rgb/1305031468.395860.png 1305031468.384700 depth/1305031468.384700.png +1305031468.428025 rgb/1305031468.428025.png 1305031468.420595 depth/1305031468.420595.png +1305031468.459759 rgb/1305031468.459759.png 1305031468.452605 depth/1305031468.452605.png +1305031468.495809 rgb/1305031468.495809.png 1305031468.488646 depth/1305031468.488646.png +1305031468.527756 rgb/1305031468.527756.png 1305031468.520786 depth/1305031468.520786.png +1305031468.559739 rgb/1305031468.559739.png 1305031468.552701 depth/1305031468.552701.png +1305031468.595768 rgb/1305031468.595768.png 1305031468.588614 depth/1305031468.588614.png +1305031468.627626 rgb/1305031468.627626.png 1305031468.620590 depth/1305031468.620590.png +1305031468.659579 rgb/1305031468.659579.png 1305031468.656644 depth/1305031468.656644.png +1305031468.695835 rgb/1305031468.695835.png 1305031468.688643 depth/1305031468.688643.png +1305031468.727785 rgb/1305031468.727785.png 1305031468.720560 depth/1305031468.720560.png +1305031468.759628 rgb/1305031468.759628.png 1305031468.756725 depth/1305031468.756725.png +1305031468.795796 rgb/1305031468.795796.png 1305031468.788562 depth/1305031468.788562.png +1305031468.829247 rgb/1305031468.829247.png 1305031468.817997 depth/1305031468.817997.png +1305031468.859659 rgb/1305031468.859659.png 1305031468.854887 depth/1305031468.854887.png +1305031468.895873 rgb/1305031468.895873.png 1305031468.889220 depth/1305031468.889220.png +1305031468.928141 rgb/1305031468.928141.png 1305031468.920539 depth/1305031468.920539.png +1305031468.959594 rgb/1305031468.959594.png 1305031468.956482 depth/1305031468.956482.png +1305031468.995711 rgb/1305031468.995711.png 1305031468.986011 depth/1305031468.986011.png +1305031469.027699 rgb/1305031469.027699.png 1305031469.020731 depth/1305031469.020731.png +1305031469.059832 rgb/1305031469.059832.png 1305031469.056318 depth/1305031469.056318.png +1305031469.095723 rgb/1305031469.095723.png 1305031469.088069 depth/1305031469.088069.png +1305031469.127679 rgb/1305031469.127679.png 1305031469.119984 depth/1305031469.119984.png +1305031469.159703 rgb/1305031469.159703.png 1305031469.155046 depth/1305031469.155046.png +1305031469.195540 rgb/1305031469.195540.png 1305031469.184648 depth/1305031469.184648.png +1305031469.227754 rgb/1305031469.227754.png 1305031469.219541 depth/1305031469.219541.png +1305031469.259586 rgb/1305031469.259586.png 1305031469.256002 depth/1305031469.256002.png +1305031469.296754 rgb/1305031469.296754.png 1305031469.288263 depth/1305031469.288263.png +1305031469.327618 rgb/1305031469.327618.png 1305031469.319772 depth/1305031469.319772.png +1305031469.359592 rgb/1305031469.359592.png 1305031469.356116 depth/1305031469.356116.png +1305031469.395695 rgb/1305031469.395695.png 1305031469.388556 depth/1305031469.388556.png +1305031469.427651 rgb/1305031469.427651.png 1305031469.420278 depth/1305031469.420278.png +1305031469.459668 rgb/1305031469.459668.png 1305031469.456563 depth/1305031469.456563.png +1305031469.495744 rgb/1305031469.495744.png 1305031469.488520 depth/1305031469.488520.png +1305031469.527622 rgb/1305031469.527622.png 1305031469.520417 depth/1305031469.520417.png +1305031469.559645 rgb/1305031469.559645.png 1305031469.556139 depth/1305031469.556139.png +1305031469.595755 rgb/1305031469.595755.png 1305031469.588500 depth/1305031469.588500.png +1305031469.627752 rgb/1305031469.627752.png 1305031469.620563 depth/1305031469.620563.png +1305031469.659590 rgb/1305031469.659590.png 1305031469.656279 depth/1305031469.656279.png +1305031469.695613 rgb/1305031469.695613.png 1305031469.687925 depth/1305031469.687925.png +1305031469.727679 rgb/1305031469.727679.png 1305031469.718943 depth/1305031469.718943.png +1305031469.759599 rgb/1305031469.759599.png 1305031469.756754 depth/1305031469.756754.png +1305031469.795621 rgb/1305031469.795621.png 1305031469.784733 depth/1305031469.784733.png +1305031469.827526 rgb/1305031469.827526.png 1305031469.820544 depth/1305031469.820544.png +1305031469.859574 rgb/1305031469.859574.png 1305031469.854359 depth/1305031469.854359.png +1305031469.895755 rgb/1305031469.895755.png 1305031469.885343 depth/1305031469.885343.png +1305031469.927854 rgb/1305031469.927854.png 1305031469.921773 depth/1305031469.921773.png +1305031469.959805 rgb/1305031469.959805.png 1305031469.953180 depth/1305031469.953180.png +1305031469.995551 rgb/1305031469.995551.png 1305031469.985327 depth/1305031469.985327.png +1305031470.027694 rgb/1305031470.027694.png 1305031470.024714 depth/1305031470.024714.png +1305031470.059638 rgb/1305031470.059638.png 1305031470.057400 depth/1305031470.057400.png +1305031470.095944 rgb/1305031470.095944.png 1305031470.088874 depth/1305031470.088874.png +1305031470.127633 rgb/1305031470.127633.png 1305031470.124820 depth/1305031470.124820.png +1305031470.159626 rgb/1305031470.159626.png 1305031470.156744 depth/1305031470.156744.png +1305031470.196092 rgb/1305031470.196092.png 1305031470.188876 depth/1305031470.188876.png +1305031470.227618 rgb/1305031470.227618.png 1305031470.224776 depth/1305031470.224776.png +1305031470.259965 rgb/1305031470.259965.png 1305031470.253015 depth/1305031470.253015.png +1305031470.295718 rgb/1305031470.295718.png 1305031470.287867 depth/1305031470.287867.png +1305031470.327644 rgb/1305031470.327644.png 1305031470.324266 depth/1305031470.324266.png +1305031470.359624 rgb/1305031470.359624.png 1305031470.356871 depth/1305031470.356871.png +1305031470.395823 rgb/1305031470.395823.png 1305031470.388056 depth/1305031470.388056.png +1305031470.427641 rgb/1305031470.427641.png 1305031470.424090 depth/1305031470.424090.png +1305031470.459721 rgb/1305031470.459721.png 1305031470.455875 depth/1305031470.455875.png +1305031470.495686 rgb/1305031470.495686.png 1305031470.487958 depth/1305031470.487958.png +1305031470.527689 rgb/1305031470.527689.png 1305031470.524431 depth/1305031470.524431.png +1305031470.559677 rgb/1305031470.559677.png 1305031470.556484 depth/1305031470.556484.png +1305031470.595760 rgb/1305031470.595760.png 1305031470.588797 depth/1305031470.588797.png +1305031470.627729 rgb/1305031470.627729.png 1305031470.624535 depth/1305031470.624535.png +1305031470.659690 rgb/1305031470.659690.png 1305031470.656787 depth/1305031470.656787.png +1305031470.695630 rgb/1305031470.695630.png 1305031470.688640 depth/1305031470.688640.png +1305031470.727654 rgb/1305031470.727654.png 1305031470.724461 depth/1305031470.724461.png +1305031470.759682 rgb/1305031470.759682.png 1305031470.755944 depth/1305031470.755944.png +1305031470.795615 rgb/1305031470.795615.png 1305031470.788407 depth/1305031470.788407.png +1305031470.827831 rgb/1305031470.827831.png 1305031470.820633 depth/1305031470.820633.png +1305031470.859645 rgb/1305031470.859645.png 1305031470.855509 depth/1305031470.855509.png +1305031470.895722 rgb/1305031470.895722.png 1305031470.886079 depth/1305031470.886079.png +1305031470.927684 rgb/1305031470.927684.png 1305031470.924410 depth/1305031470.924410.png +1305031470.959647 rgb/1305031470.959647.png 1305031470.956439 depth/1305031470.956439.png +1305031470.995996 rgb/1305031470.995996.png 1305031470.988276 depth/1305031470.988276.png +1305031471.027644 rgb/1305031471.027644.png 1305031471.024309 depth/1305031471.024309.png +1305031471.059636 rgb/1305031471.059636.png 1305031471.056616 depth/1305031471.056616.png +1305031471.095777 rgb/1305031471.095777.png 1305031471.088440 depth/1305031471.088440.png +1305031471.127663 rgb/1305031471.127663.png 1305031471.123837 depth/1305031471.123837.png +1305031471.159649 rgb/1305031471.159649.png 1305031471.155886 depth/1305031471.155886.png +1305031471.195703 rgb/1305031471.195703.png 1305031471.192698 depth/1305031471.192698.png +1305031471.227569 rgb/1305031471.227569.png 1305031471.224404 depth/1305031471.224404.png +1305031471.259722 rgb/1305031471.259722.png 1305031471.256397 depth/1305031471.256397.png +1305031471.296068 rgb/1305031471.296068.png 1305031471.288603 depth/1305031471.288603.png +1305031471.327642 rgb/1305031471.327642.png 1305031471.324440 depth/1305031471.324440.png +1305031471.359615 rgb/1305031471.359615.png 1305031471.356569 depth/1305031471.356569.png +1305031471.395730 rgb/1305031471.395730.png 1305031471.392751 depth/1305031471.392751.png +1305031471.427704 rgb/1305031471.427704.png 1305031471.424494 depth/1305031471.424494.png +1305031471.459647 rgb/1305031471.459647.png 1305031471.456975 depth/1305031471.456975.png +1305031471.496491 rgb/1305031471.496491.png 1305031471.492705 depth/1305031471.492705.png +1305031471.527624 rgb/1305031471.527624.png 1305031471.524343 depth/1305031471.524343.png +1305031471.559671 rgb/1305031471.559671.png 1305031471.556561 depth/1305031471.556561.png +1305031471.595702 rgb/1305031471.595702.png 1305031471.592606 depth/1305031471.592606.png +1305031471.627621 rgb/1305031471.627621.png 1305031471.624486 depth/1305031471.624486.png +1305031471.659642 rgb/1305031471.659642.png 1305031471.656831 depth/1305031471.656831.png +1305031471.695609 rgb/1305031471.695609.png 1305031471.693182 depth/1305031471.693182.png +1305031471.727501 rgb/1305031471.727501.png 1305031471.724753 depth/1305031471.724753.png +1305031471.759702 rgb/1305031471.759702.png 1305031471.753002 depth/1305031471.753002.png +1305031471.795801 rgb/1305031471.795801.png 1305031471.792706 depth/1305031471.792706.png +1305031471.827639 rgb/1305031471.827639.png 1305031471.823821 depth/1305031471.823821.png +1305031471.859665 rgb/1305031471.859665.png 1305031471.855793 depth/1305031471.855793.png +1305031471.895604 rgb/1305031471.895604.png 1305031471.892838 depth/1305031471.892838.png +1305031471.927651 rgb/1305031471.927651.png 1305031471.924928 depth/1305031471.924928.png +1305031471.959643 rgb/1305031471.959643.png 1305031471.957162 depth/1305031471.957162.png +1305031471.995573 rgb/1305031471.995573.png 1305031471.993177 depth/1305031471.993177.png +1305031472.027638 rgb/1305031472.027638.png 1305031472.024660 depth/1305031472.024660.png +1305031472.059668 rgb/1305031472.059668.png 1305031472.058063 depth/1305031472.058063.png +1305031472.095601 rgb/1305031472.095601.png 1305031472.092883 depth/1305031472.092883.png +1305031472.127594 rgb/1305031472.127594.png 1305031472.124760 depth/1305031472.124760.png +1305031472.159645 rgb/1305031472.159645.png 1305031472.156982 depth/1305031472.156982.png +1305031472.195682 rgb/1305031472.195682.png 1305031472.192890 depth/1305031472.192890.png +1305031472.227626 rgb/1305031472.227626.png 1305031472.224678 depth/1305031472.224678.png +1305031472.263840 rgb/1305031472.263840.png 1305031472.256642 depth/1305031472.256642.png +1305031472.295671 rgb/1305031472.295671.png 1305031472.293139 depth/1305031472.293139.png +1305031472.327678 rgb/1305031472.327678.png 1305031472.324844 depth/1305031472.324844.png +1305031472.363577 rgb/1305031472.363577.png 1305031472.360912 depth/1305031472.360912.png +1305031472.395599 rgb/1305031472.395599.png 1305031472.392956 depth/1305031472.392956.png +1305031472.427686 rgb/1305031472.427686.png 1305031472.424694 depth/1305031472.424694.png +1305031472.463603 rgb/1305031472.463603.png 1305031472.460919 depth/1305031472.460919.png +1305031472.495626 rgb/1305031472.495626.png 1305031472.492972 depth/1305031472.492972.png +1305031472.527625 rgb/1305031472.527625.png 1305031472.524781 depth/1305031472.524781.png +1305031472.563587 rgb/1305031472.563587.png 1305031472.561296 depth/1305031472.561296.png +1305031472.595675 rgb/1305031472.595675.png 1305031472.592968 depth/1305031472.592968.png +1305031472.627701 rgb/1305031472.627701.png 1305031472.624647 depth/1305031472.624647.png +1305031472.663575 rgb/1305031472.663575.png 1305031472.660836 depth/1305031472.660836.png +1305031472.695755 rgb/1305031472.695755.png 1305031472.693008 depth/1305031472.693008.png +1305031472.727628 rgb/1305031472.727628.png 1305031472.724752 depth/1305031472.724752.png +1305031472.763578 rgb/1305031472.763578.png 1305031472.760654 depth/1305031472.760654.png +1305031472.795640 rgb/1305031472.795640.png 1305031472.792775 depth/1305031472.792775.png +1305031472.827627 rgb/1305031472.827627.png 1305031472.824692 depth/1305031472.824692.png +1305031472.863598 rgb/1305031472.863598.png 1305031472.860936 depth/1305031472.860936.png +1305031472.895713 rgb/1305031472.895713.png 1305031472.892944 depth/1305031472.892944.png +1305031472.927685 rgb/1305031472.927685.png 1305031472.924814 depth/1305031472.924814.png +1305031472.963756 rgb/1305031472.963756.png 1305031472.961213 depth/1305031472.961213.png +1305031472.995704 rgb/1305031472.995704.png 1305031472.992815 depth/1305031472.992815.png +1305031473.027638 rgb/1305031473.027638.png 1305031473.024564 depth/1305031473.024564.png +1305031473.063684 rgb/1305031473.063684.png 1305031473.060795 depth/1305031473.060795.png +1305031473.095695 rgb/1305031473.095695.png 1305031473.092012 depth/1305031473.092012.png +1305031473.127744 rgb/1305031473.127744.png 1305031473.124072 depth/1305031473.124072.png +1305031473.167060 rgb/1305031473.167060.png 1305031473.158420 depth/1305031473.158420.png +1305031473.196069 rgb/1305031473.196069.png 1305031473.190828 depth/1305031473.190828.png diff --git a/vSLAM/ch8/data/depth.txt b/vSLAM/ch8/data/depth.txt new file mode 100644 index 00000000..ad3db046 --- /dev/null +++ b/vSLAM/ch8/data/depth.txt @@ -0,0 +1,598 @@ +# depth maps +# file: 'rgbd_dataset_freiburg1_desk.bag' +# timestamp filename +1305031453.374112 depth/1305031453.374112.png +1305031453.404816 depth/1305031453.404816.png +1305031453.436941 depth/1305031453.436941.png +1305031453.473352 depth/1305031453.473352.png +1305031453.505218 depth/1305031453.505218.png +1305031453.538301 depth/1305031453.538301.png +1305031453.574074 depth/1305031453.574074.png +1305031453.605314 depth/1305031453.605314.png +1305031453.636951 depth/1305031453.636951.png +1305031453.673185 depth/1305031453.673185.png +1305031453.705487 depth/1305031453.705487.png +1305031453.736856 depth/1305031453.736856.png +1305031453.773786 depth/1305031453.773786.png +1305031453.805041 depth/1305031453.805041.png +1305031453.840352 depth/1305031453.840352.png +1305031453.869618 depth/1305031453.869618.png +1305031453.905519 depth/1305031453.905519.png +1305031453.940012 depth/1305031453.940012.png +1305031453.972592 depth/1305031453.972592.png +1305031454.003179 depth/1305031454.003179.png +1305031454.040976 depth/1305031454.040976.png +1305031454.072690 depth/1305031454.072690.png +1305031454.104619 depth/1305031454.104619.png +1305031454.141030 depth/1305031454.141030.png +1305031454.172688 depth/1305031454.172688.png +1305031454.204626 depth/1305031454.204626.png +1305031454.240858 depth/1305031454.240858.png +1305031454.273489 depth/1305031454.273489.png +1305031454.304744 depth/1305031454.304744.png +1305031454.340806 depth/1305031454.340806.png +1305031454.372652 depth/1305031454.372652.png +1305031454.401962 depth/1305031454.401962.png +1305031454.437248 depth/1305031454.437248.png +1305031454.470741 depth/1305031454.470741.png +1305031454.503859 depth/1305031454.503859.png +1305031454.538424 depth/1305031454.538424.png +1305031454.570323 depth/1305031454.570323.png +1305031454.602019 depth/1305031454.602019.png +1305031454.639284 depth/1305031454.639284.png +1305031454.669573 depth/1305031454.669573.png +1305031454.702030 depth/1305031454.702030.png +1305031454.740764 depth/1305031454.740764.png +1305031454.772865 depth/1305031454.772865.png +1305031454.802574 depth/1305031454.802574.png +1305031454.840500 depth/1305031454.840500.png +1305031454.870269 depth/1305031454.870269.png +1305031454.901065 depth/1305031454.901065.png +1305031454.940240 depth/1305031454.940240.png +1305031454.973081 depth/1305031454.973081.png +1305031455.010759 depth/1305031455.010759.png +1305031455.040446 depth/1305031455.040446.png +1305031455.074282 depth/1305031455.074282.png +1305031455.110340 depth/1305031455.110340.png +1305031455.142700 depth/1305031455.142700.png +1305031455.172771 depth/1305031455.172771.png +1305031455.210307 depth/1305031455.210307.png +1305031455.240960 depth/1305031455.240960.png +1305031455.273001 depth/1305031455.273001.png +1305031455.310303 depth/1305031455.310303.png +1305031455.342381 depth/1305031455.342381.png +1305031455.374120 depth/1305031455.374120.png +1305031455.409213 depth/1305031455.409213.png +1305031455.442380 depth/1305031455.442380.png +1305031455.473168 depth/1305031455.473168.png +1305031455.509397 depth/1305031455.509397.png +1305031455.540835 depth/1305031455.540835.png +1305031455.572996 depth/1305031455.572996.png +1305031455.608802 depth/1305031455.608802.png +1305031455.641333 depth/1305031455.641333.png +1305031455.672887 depth/1305031455.672887.png +1305031455.707680 depth/1305031455.707680.png +1305031455.742005 depth/1305031455.742005.png +1305031455.773667 depth/1305031455.773667.png +1305031455.809109 depth/1305031455.809109.png +1305031455.838364 depth/1305031455.838364.png +1305031455.872220 depth/1305031455.872220.png +1305031455.908418 depth/1305031455.908418.png +1305031455.939606 depth/1305031455.939606.png +1305031455.973594 depth/1305031455.973594.png +1305031456.008998 depth/1305031456.008998.png +1305031456.041930 depth/1305031456.041930.png +1305031456.073846 depth/1305031456.073846.png +1305031456.108963 depth/1305031456.108963.png +1305031456.140836 depth/1305031456.140836.png +1305031456.173198 depth/1305031456.173198.png +1305031456.208934 depth/1305031456.208934.png +1305031456.240996 depth/1305031456.240996.png +1305031456.277928 depth/1305031456.277928.png +1305031456.310040 depth/1305031456.310040.png +1305031456.341659 depth/1305031456.341659.png +1305031456.377115 depth/1305031456.377115.png +1305031456.409172 depth/1305031456.409172.png +1305031456.440717 depth/1305031456.440717.png +1305031456.476027 depth/1305031456.476027.png +1305031456.508911 depth/1305031456.508911.png +1305031456.541832 depth/1305031456.541832.png +1305031456.576087 depth/1305031456.576087.png +1305031456.607930 depth/1305031456.607930.png +1305031456.640699 depth/1305031456.640699.png +1305031456.675835 depth/1305031456.675835.png +1305031456.709099 depth/1305031456.709099.png +1305031456.740863 depth/1305031456.740863.png +1305031456.777218 depth/1305031456.777218.png +1305031456.808986 depth/1305031456.808986.png +1305031456.841050 depth/1305031456.841050.png +1305031456.878006 depth/1305031456.878006.png +1305031456.909883 depth/1305031456.909883.png +1305031456.942298 depth/1305031456.942298.png +1305031456.977139 depth/1305031456.977139.png +1305031457.006193 depth/1305031457.006193.png +1305031457.042512 depth/1305031457.042512.png +1305031457.076011 depth/1305031457.076011.png +1305031457.108053 depth/1305031457.108053.png +1305031457.142120 depth/1305031457.142120.png +1305031457.177463 depth/1305031457.177463.png +1305031457.209336 depth/1305031457.209336.png +1305031457.240792 depth/1305031457.240792.png +1305031457.277247 depth/1305031457.277247.png +1305031457.309693 depth/1305031457.309693.png +1305031457.342954 depth/1305031457.342954.png +1305031457.376037 depth/1305031457.376037.png +1305031457.407980 depth/1305031457.407980.png +1305031457.441357 depth/1305031457.441357.png +1305031457.476577 depth/1305031457.476577.png +1305031457.508603 depth/1305031457.508603.png +1305031457.543946 depth/1305031457.543946.png +1305031457.576581 depth/1305031457.576581.png +1305031457.607246 depth/1305031457.607246.png +1305031457.643534 depth/1305031457.643534.png +1305031457.675414 depth/1305031457.675414.png +1305031457.707739 depth/1305031457.707739.png +1305031457.745071 depth/1305031457.745071.png +1305031457.773518 depth/1305031457.773518.png +1305031457.807824 depth/1305031457.807824.png +1305031457.842853 depth/1305031457.842853.png +1305031457.875920 depth/1305031457.875920.png +1305031457.906126 depth/1305031457.906126.png +1305031457.942604 depth/1305031457.942604.png +1305031457.976744 depth/1305031457.976744.png +1305031458.009019 depth/1305031458.009019.png +1305031458.046303 depth/1305031458.046303.png +1305031458.077315 depth/1305031458.077315.png +1305031458.108896 depth/1305031458.108896.png +1305031458.144808 depth/1305031458.144808.png +1305031458.178039 depth/1305031458.178039.png +1305031458.209384 depth/1305031458.209384.png +1305031458.245729 depth/1305031458.245729.png +1305031458.277447 depth/1305031458.277447.png +1305031458.308343 depth/1305031458.308343.png +1305031458.343898 depth/1305031458.343898.png +1305031458.376213 depth/1305031458.376213.png +1305031458.407856 depth/1305031458.407856.png +1305031458.443957 depth/1305031458.443957.png +1305031458.476034 depth/1305031458.476034.png +1305031458.508869 depth/1305031458.508869.png +1305031458.544401 depth/1305031458.544401.png +1305031458.576178 depth/1305031458.576178.png +1305031458.608421 depth/1305031458.608421.png +1305031458.643659 depth/1305031458.643659.png +1305031458.676991 depth/1305031458.676991.png +1305031458.707780 depth/1305031458.707780.png +1305031458.744924 depth/1305031458.744924.png +1305031458.773802 depth/1305031458.773802.png +1305031458.810621 depth/1305031458.810621.png +1305031458.842919 depth/1305031458.842919.png +1305031458.875889 depth/1305031458.875889.png +1305031458.910599 depth/1305031458.910599.png +1305031458.943997 depth/1305031458.943997.png +1305031458.976007 depth/1305031458.976007.png +1305031459.012560 depth/1305031459.012560.png +1305031459.044413 depth/1305031459.044413.png +1305031459.073657 depth/1305031459.073657.png +1305031459.112711 depth/1305031459.112711.png +1305031459.144497 depth/1305031459.144497.png +1305031459.176463 depth/1305031459.176463.png +1305031459.208791 depth/1305031459.208791.png +1305031459.244159 depth/1305031459.244159.png +1305031459.274941 depth/1305031459.274941.png +1305031459.311921 depth/1305031459.311921.png +1305031459.344169 depth/1305031459.344169.png +1305031459.374084 depth/1305031459.374084.png +1305031459.408831 depth/1305031459.408831.png +1305031459.443181 depth/1305031459.443181.png +1305031459.473401 depth/1305031459.473401.png +1305031459.510267 depth/1305031459.510267.png +1305031459.544431 depth/1305031459.544431.png +1305031459.576817 depth/1305031459.576817.png +1305031459.611939 depth/1305031459.611939.png +1305031459.643453 depth/1305031459.643453.png +1305031459.675678 depth/1305031459.675678.png +1305031459.711531 depth/1305031459.711531.png +1305031459.743425 depth/1305031459.743425.png +1305031459.776577 depth/1305031459.776577.png +1305031459.812562 depth/1305031459.812562.png +1305031459.844736 depth/1305031459.844736.png +1305031459.877006 depth/1305031459.877006.png +1305031459.911472 depth/1305031459.911472.png +1305031459.943616 depth/1305031459.943616.png +1305031459.979430 depth/1305031459.979430.png +1305031460.011909 depth/1305031460.011909.png +1305031460.043717 depth/1305031460.043717.png +1305031460.079449 depth/1305031460.079449.png +1305031460.111951 depth/1305031460.111951.png +1305031460.144204 depth/1305031460.144204.png +1305031460.178730 depth/1305031460.178730.png +1305031460.208637 depth/1305031460.208637.png +1305031460.243467 depth/1305031460.243467.png +1305031460.279164 depth/1305031460.279164.png +1305031460.311712 depth/1305031460.311712.png +1305031460.342879 depth/1305031460.342879.png +1305031460.377806 depth/1305031460.377806.png +1305031460.409883 depth/1305031460.409883.png +1305031460.444036 depth/1305031460.444036.png +1305031460.479856 depth/1305031460.479856.png +1305031460.508966 depth/1305031460.508966.png +1305031460.544245 depth/1305031460.544245.png +1305031460.579561 depth/1305031460.579561.png +1305031460.612190 depth/1305031460.612190.png +1305031460.644011 depth/1305031460.644011.png +1305031460.679350 depth/1305031460.679350.png +1305031460.711684 depth/1305031460.711684.png +1305031460.743767 depth/1305031460.743767.png +1305031460.779201 depth/1305031460.779201.png +1305031460.811318 depth/1305031460.811318.png +1305031460.843836 depth/1305031460.843836.png +1305031460.879093 depth/1305031460.879093.png +1305031460.911313 depth/1305031460.911313.png +1305031460.943375 depth/1305031460.943375.png +1305031460.979083 depth/1305031460.979083.png +1305031461.011290 depth/1305031461.011290.png +1305031461.043398 depth/1305031461.043398.png +1305031461.079602 depth/1305031461.079602.png +1305031461.111961 depth/1305031461.111961.png +1305031461.144098 depth/1305031461.144098.png +1305031461.179883 depth/1305031461.179883.png +1305031461.211180 depth/1305031461.211180.png +1305031461.246864 depth/1305031461.246864.png +1305031461.278888 depth/1305031461.278888.png +1305031461.311240 depth/1305031461.311240.png +1305031461.346875 depth/1305031461.346875.png +1305031461.378850 depth/1305031461.378850.png +1305031461.411130 depth/1305031461.411130.png +1305031461.447015 depth/1305031461.447015.png +1305031461.478901 depth/1305031461.478901.png +1305031461.512120 depth/1305031461.512120.png +1305031461.547338 depth/1305031461.547338.png +1305031461.578847 depth/1305031461.578847.png +1305031461.609662 depth/1305031461.609662.png +1305031461.646970 depth/1305031461.646970.png +1305031461.676203 depth/1305031461.676203.png +1305031461.711212 depth/1305031461.711212.png +1305031461.746919 depth/1305031461.746919.png +1305031461.778616 depth/1305031461.778616.png +1305031461.811319 depth/1305031461.811319.png +1305031461.847090 depth/1305031461.847090.png +1305031461.879162 depth/1305031461.879162.png +1305031461.911121 depth/1305031461.911121.png +1305031461.947264 depth/1305031461.947264.png +1305031461.979223 depth/1305031461.979223.png +1305031462.011791 depth/1305031462.011791.png +1305031462.047463 depth/1305031462.047463.png +1305031462.079285 depth/1305031462.079285.png +1305031462.112081 depth/1305031462.112081.png +1305031462.147634 depth/1305031462.147634.png +1305031462.179358 depth/1305031462.179358.png +1305031462.212836 depth/1305031462.212836.png +1305031462.248986 depth/1305031462.248986.png +1305031462.280774 depth/1305031462.280774.png +1305031462.311931 depth/1305031462.311931.png +1305031462.347816 depth/1305031462.347816.png +1305031462.379950 depth/1305031462.379950.png +1305031462.413016 depth/1305031462.413016.png +1305031462.448295 depth/1305031462.448295.png +1305031462.480843 depth/1305031462.480843.png +1305031462.517041 depth/1305031462.517041.png +1305031462.548959 depth/1305031462.548959.png +1305031462.581088 depth/1305031462.581088.png +1305031462.617123 depth/1305031462.617123.png +1305031462.648708 depth/1305031462.648708.png +1305031462.680788 depth/1305031462.680788.png +1305031462.716812 depth/1305031462.716812.png +1305031462.748732 depth/1305031462.748732.png +1305031462.780885 depth/1305031462.780885.png +1305031462.816821 depth/1305031462.816821.png +1305031462.848525 depth/1305031462.848525.png +1305031462.880471 depth/1305031462.880471.png +1305031462.916800 depth/1305031462.916800.png +1305031462.947939 depth/1305031462.947939.png +1305031462.979943 depth/1305031462.979943.png +1305031463.016121 depth/1305031463.016121.png +1305031463.050783 depth/1305031463.050783.png +1305031463.076870 depth/1305031463.076870.png +1305031463.116806 depth/1305031463.116806.png +1305031463.148565 depth/1305031463.148565.png +1305031463.180505 depth/1305031463.180505.png +1305031463.217123 depth/1305031463.217123.png +1305031463.248719 depth/1305031463.248719.png +1305031463.278737 depth/1305031463.278737.png +1305031463.317110 depth/1305031463.317110.png +1305031463.348740 depth/1305031463.348740.png +1305031463.380514 depth/1305031463.380514.png +1305031463.416326 depth/1305031463.416326.png +1305031463.444773 depth/1305031463.444773.png +1305031463.480415 depth/1305031463.480415.png +1305031463.516994 depth/1305031463.516994.png +1305031463.548505 depth/1305031463.548505.png +1305031463.580684 depth/1305031463.580684.png +1305031463.616671 depth/1305031463.616671.png +1305031463.646147 depth/1305031463.646147.png +1305031463.683908 depth/1305031463.683908.png +1305031463.716110 depth/1305031463.716110.png +1305031463.747849 depth/1305031463.747849.png +1305031463.783912 depth/1305031463.783912.png +1305031463.815883 depth/1305031463.815883.png +1305031463.848094 depth/1305031463.848094.png +1305031463.883817 depth/1305031463.883817.png +1305031463.917433 depth/1305031463.917433.png +1305031463.944435 depth/1305031463.944435.png +1305031463.983748 depth/1305031463.983748.png +1305031464.015867 depth/1305031464.015867.png +1305031464.047778 depth/1305031464.047778.png +1305031464.083152 depth/1305031464.083152.png +1305031464.115837 depth/1305031464.115837.png +1305031464.147663 depth/1305031464.147663.png +1305031464.183566 depth/1305031464.183566.png +1305031464.212447 depth/1305031464.212447.png +1305031464.247602 depth/1305031464.247602.png +1305031464.283694 depth/1305031464.283694.png +1305031464.315699 depth/1305031464.315699.png +1305031464.347553 depth/1305031464.347553.png +1305031464.383465 depth/1305031464.383465.png +1305031464.415539 depth/1305031464.415539.png +1305031464.444269 depth/1305031464.444269.png +1305031464.487561 depth/1305031464.487561.png +1305031464.513688 depth/1305031464.513688.png +1305031464.548007 depth/1305031464.548007.png +1305031464.584260 depth/1305031464.584260.png +1305031464.615688 depth/1305031464.615688.png +1305031464.648851 depth/1305031464.648851.png +1305031464.684318 depth/1305031464.684318.png +1305031464.716305 depth/1305031464.716305.png +1305031464.748588 depth/1305031464.748588.png +1305031464.784268 depth/1305031464.784268.png +1305031464.816195 depth/1305031464.816195.png +1305031464.848283 depth/1305031464.848283.png +1305031464.884177 depth/1305031464.884177.png +1305031464.916391 depth/1305031464.916391.png +1305031464.952471 depth/1305031464.952471.png +1305031464.984257 depth/1305031464.984257.png +1305031465.015390 depth/1305031465.015390.png +1305031465.048430 depth/1305031465.048430.png +1305031465.083338 depth/1305031465.083338.png +1305031465.115475 depth/1305031465.115475.png +1305031465.151558 depth/1305031465.151558.png +1305031465.183558 depth/1305031465.183558.png +1305031465.215832 depth/1305031465.215832.png +1305031465.251788 depth/1305031465.251788.png +1305031465.283737 depth/1305031465.283737.png +1305031465.315985 depth/1305031465.315985.png +1305031465.351729 depth/1305031465.351729.png +1305031465.383701 depth/1305031465.383701.png +1305031465.416543 depth/1305031465.416543.png +1305031465.452401 depth/1305031465.452401.png +1305031465.483803 depth/1305031465.483803.png +1305031465.516043 depth/1305031465.516043.png +1305031465.551838 depth/1305031465.551838.png +1305031465.583570 depth/1305031465.583570.png +1305031465.615685 depth/1305031465.615685.png +1305031465.651645 depth/1305031465.651645.png +1305031465.684759 depth/1305031465.684759.png +1305031465.716279 depth/1305031465.716279.png +1305031465.753153 depth/1305031465.753153.png +1305031465.784387 depth/1305031465.784387.png +1305031465.816591 depth/1305031465.816591.png +1305031465.852860 depth/1305031465.852860.png +1305031465.884370 depth/1305031465.884370.png +1305031465.912828 depth/1305031465.912828.png +1305031465.952840 depth/1305031465.952840.png +1305031465.984183 depth/1305031465.984183.png +1305031466.016599 depth/1305031466.016599.png +1305031466.052655 depth/1305031466.052655.png +1305031466.083913 depth/1305031466.083913.png +1305031466.116400 depth/1305031466.116400.png +1305031466.152540 depth/1305031466.152540.png +1305031466.184186 depth/1305031466.184186.png +1305031466.220477 depth/1305031466.220477.png +1305031466.252491 depth/1305031466.252491.png +1305031466.284389 depth/1305031466.284389.png +1305031466.320055 depth/1305031466.320055.png +1305031466.352082 depth/1305031466.352082.png +1305031466.384479 depth/1305031466.384479.png +1305031466.420844 depth/1305031466.420844.png +1305031466.452369 depth/1305031466.452369.png +1305031466.483315 depth/1305031466.483315.png +1305031466.519548 depth/1305031466.519548.png +1305031466.552219 depth/1305031466.552219.png +1305031466.584438 depth/1305031466.584438.png +1305031466.620424 depth/1305031466.620424.png +1305031466.648654 depth/1305031466.648654.png +1305031466.684412 depth/1305031466.684412.png +1305031466.719744 depth/1305031466.719744.png +1305031466.748734 depth/1305031466.748734.png +1305031466.784300 depth/1305031466.784300.png +1305031466.819502 depth/1305031466.819502.png +1305031466.851527 depth/1305031466.851527.png +1305031466.883430 depth/1305031466.883430.png +1305031466.919411 depth/1305031466.919411.png +1305031466.952451 depth/1305031466.952451.png +1305031466.984027 depth/1305031466.984027.png +1305031467.020424 depth/1305031467.020424.png +1305031467.052391 depth/1305031467.052391.png +1305031467.084130 depth/1305031467.084130.png +1305031467.120528 depth/1305031467.120528.png +1305031467.152363 depth/1305031467.152363.png +1305031467.184216 depth/1305031467.184216.png +1305031467.220466 depth/1305031467.220466.png +1305031467.252275 depth/1305031467.252275.png +1305031467.284258 depth/1305031467.284258.png +1305031467.318028 depth/1305031467.318028.png +1305031467.349355 depth/1305031467.349355.png +1305031467.383844 depth/1305031467.383844.png +1305031467.420160 depth/1305031467.420160.png +1305031467.452057 depth/1305031467.452057.png +1305031467.484357 depth/1305031467.484357.png +1305031467.520535 depth/1305031467.520535.png +1305031467.552164 depth/1305031467.552164.png +1305031467.584354 depth/1305031467.584354.png +1305031467.618680 depth/1305031467.618680.png +1305031467.651977 depth/1305031467.651977.png +1305031467.686044 depth/1305031467.686044.png +1305031467.718326 depth/1305031467.718326.png +1305031467.752580 depth/1305031467.752580.png +1305031467.788562 depth/1305031467.788562.png +1305031467.820454 depth/1305031467.820454.png +1305031467.852678 depth/1305031467.852678.png +1305031467.888472 depth/1305031467.888472.png +1305031467.920800 depth/1305031467.920800.png +1305031467.952485 depth/1305031467.952485.png +1305031467.988523 depth/1305031467.988523.png +1305031468.020491 depth/1305031468.020491.png +1305031468.052668 depth/1305031468.052668.png +1305031468.088379 depth/1305031468.088379.png +1305031468.120522 depth/1305031468.120522.png +1305031468.152356 depth/1305031468.152356.png +1305031468.188327 depth/1305031468.188327.png +1305031468.220648 depth/1305031468.220648.png +1305031468.252517 depth/1305031468.252517.png +1305031468.288361 depth/1305031468.288361.png +1305031468.320522 depth/1305031468.320522.png +1305031468.352594 depth/1305031468.352594.png +1305031468.384700 depth/1305031468.384700.png +1305031468.420595 depth/1305031468.420595.png +1305031468.452605 depth/1305031468.452605.png +1305031468.488646 depth/1305031468.488646.png +1305031468.520786 depth/1305031468.520786.png +1305031468.552701 depth/1305031468.552701.png +1305031468.588614 depth/1305031468.588614.png +1305031468.620590 depth/1305031468.620590.png +1305031468.656644 depth/1305031468.656644.png +1305031468.688643 depth/1305031468.688643.png +1305031468.720560 depth/1305031468.720560.png +1305031468.756725 depth/1305031468.756725.png +1305031468.788562 depth/1305031468.788562.png +1305031468.817997 depth/1305031468.817997.png +1305031468.854887 depth/1305031468.854887.png +1305031468.889220 depth/1305031468.889220.png +1305031468.920539 depth/1305031468.920539.png +1305031468.956482 depth/1305031468.956482.png +1305031468.986011 depth/1305031468.986011.png +1305031469.020731 depth/1305031469.020731.png +1305031469.056318 depth/1305031469.056318.png +1305031469.088069 depth/1305031469.088069.png +1305031469.119984 depth/1305031469.119984.png +1305031469.155046 depth/1305031469.155046.png +1305031469.184648 depth/1305031469.184648.png +1305031469.219541 depth/1305031469.219541.png +1305031469.256002 depth/1305031469.256002.png +1305031469.288263 depth/1305031469.288263.png +1305031469.319772 depth/1305031469.319772.png +1305031469.356116 depth/1305031469.356116.png +1305031469.388556 depth/1305031469.388556.png +1305031469.420278 depth/1305031469.420278.png +1305031469.456563 depth/1305031469.456563.png +1305031469.488520 depth/1305031469.488520.png +1305031469.520417 depth/1305031469.520417.png +1305031469.556139 depth/1305031469.556139.png +1305031469.588500 depth/1305031469.588500.png +1305031469.620563 depth/1305031469.620563.png +1305031469.656279 depth/1305031469.656279.png +1305031469.687925 depth/1305031469.687925.png +1305031469.718943 depth/1305031469.718943.png +1305031469.756754 depth/1305031469.756754.png +1305031469.784733 depth/1305031469.784733.png +1305031469.820544 depth/1305031469.820544.png +1305031469.854359 depth/1305031469.854359.png +1305031469.885343 depth/1305031469.885343.png +1305031469.921773 depth/1305031469.921773.png +1305031469.953180 depth/1305031469.953180.png +1305031469.985327 depth/1305031469.985327.png +1305031470.024714 depth/1305031470.024714.png +1305031470.057400 depth/1305031470.057400.png +1305031470.088874 depth/1305031470.088874.png +1305031470.124820 depth/1305031470.124820.png +1305031470.156744 depth/1305031470.156744.png +1305031470.188876 depth/1305031470.188876.png +1305031470.224776 depth/1305031470.224776.png +1305031470.253015 depth/1305031470.253015.png +1305031470.287867 depth/1305031470.287867.png +1305031470.324266 depth/1305031470.324266.png +1305031470.356871 depth/1305031470.356871.png +1305031470.388056 depth/1305031470.388056.png +1305031470.424090 depth/1305031470.424090.png +1305031470.455875 depth/1305031470.455875.png +1305031470.487958 depth/1305031470.487958.png +1305031470.524431 depth/1305031470.524431.png +1305031470.556484 depth/1305031470.556484.png +1305031470.588797 depth/1305031470.588797.png +1305031470.624535 depth/1305031470.624535.png +1305031470.656787 depth/1305031470.656787.png +1305031470.688640 depth/1305031470.688640.png +1305031470.724461 depth/1305031470.724461.png +1305031470.755944 depth/1305031470.755944.png +1305031470.788407 depth/1305031470.788407.png +1305031470.820633 depth/1305031470.820633.png +1305031470.855509 depth/1305031470.855509.png +1305031470.886079 depth/1305031470.886079.png +1305031470.924410 depth/1305031470.924410.png +1305031470.956439 depth/1305031470.956439.png +1305031470.988276 depth/1305031470.988276.png +1305031471.024309 depth/1305031471.024309.png +1305031471.056616 depth/1305031471.056616.png +1305031471.088440 depth/1305031471.088440.png +1305031471.123837 depth/1305031471.123837.png +1305031471.155886 depth/1305031471.155886.png +1305031471.192698 depth/1305031471.192698.png +1305031471.224404 depth/1305031471.224404.png +1305031471.256397 depth/1305031471.256397.png +1305031471.288603 depth/1305031471.288603.png +1305031471.324440 depth/1305031471.324440.png +1305031471.356569 depth/1305031471.356569.png +1305031471.392751 depth/1305031471.392751.png +1305031471.424494 depth/1305031471.424494.png +1305031471.456975 depth/1305031471.456975.png +1305031471.492705 depth/1305031471.492705.png +1305031471.524343 depth/1305031471.524343.png +1305031471.556561 depth/1305031471.556561.png +1305031471.592606 depth/1305031471.592606.png +1305031471.624486 depth/1305031471.624486.png +1305031471.656831 depth/1305031471.656831.png +1305031471.693182 depth/1305031471.693182.png +1305031471.724753 depth/1305031471.724753.png +1305031471.753002 depth/1305031471.753002.png +1305031471.792706 depth/1305031471.792706.png +1305031471.823821 depth/1305031471.823821.png +1305031471.855793 depth/1305031471.855793.png +1305031471.892838 depth/1305031471.892838.png +1305031471.924928 depth/1305031471.924928.png +1305031471.957162 depth/1305031471.957162.png +1305031471.993177 depth/1305031471.993177.png +1305031472.024660 depth/1305031472.024660.png +1305031472.058063 depth/1305031472.058063.png +1305031472.092883 depth/1305031472.092883.png +1305031472.124760 depth/1305031472.124760.png +1305031472.156982 depth/1305031472.156982.png +1305031472.192890 depth/1305031472.192890.png +1305031472.224678 depth/1305031472.224678.png +1305031472.256642 depth/1305031472.256642.png +1305031472.293139 depth/1305031472.293139.png +1305031472.324844 depth/1305031472.324844.png +1305031472.360912 depth/1305031472.360912.png +1305031472.392956 depth/1305031472.392956.png +1305031472.424694 depth/1305031472.424694.png +1305031472.460919 depth/1305031472.460919.png +1305031472.492972 depth/1305031472.492972.png +1305031472.524781 depth/1305031472.524781.png +1305031472.561296 depth/1305031472.561296.png +1305031472.592968 depth/1305031472.592968.png +1305031472.624647 depth/1305031472.624647.png +1305031472.660836 depth/1305031472.660836.png +1305031472.693008 depth/1305031472.693008.png +1305031472.724752 depth/1305031472.724752.png +1305031472.760654 depth/1305031472.760654.png +1305031472.792775 depth/1305031472.792775.png +1305031472.824692 depth/1305031472.824692.png +1305031472.860936 depth/1305031472.860936.png +1305031472.892944 depth/1305031472.892944.png +1305031472.924814 depth/1305031472.924814.png +1305031472.961213 depth/1305031472.961213.png +1305031472.992815 depth/1305031472.992815.png +1305031473.024564 depth/1305031473.024564.png +1305031473.060795 depth/1305031473.060795.png +1305031473.092012 depth/1305031473.092012.png +1305031473.124072 depth/1305031473.124072.png +1305031473.158420 depth/1305031473.158420.png +1305031473.190828 depth/1305031473.190828.png diff --git a/vSLAM/ch8/data/depth/1305031453.374112.png b/vSLAM/ch8/data/depth/1305031453.374112.png new file mode 100644 index 00000000..641f7349 Binary files /dev/null and b/vSLAM/ch8/data/depth/1305031453.374112.png differ diff --git a/vSLAM/ch8/data/depth/1305031453.404816.png b/vSLAM/ch8/data/depth/1305031453.404816.png new file mode 100644 index 00000000..8038976c Binary files /dev/null and b/vSLAM/ch8/data/depth/1305031453.404816.png differ diff --git a/vSLAM/ch8/data/depth/1305031453.436941.png b/vSLAM/ch8/data/depth/1305031453.436941.png new file mode 100644 index 00000000..b28dd7e0 Binary files /dev/null and b/vSLAM/ch8/data/depth/1305031453.436941.png differ diff --git a/vSLAM/ch8/data/depth/1305031453.473352.png b/vSLAM/ch8/data/depth/1305031453.473352.png new file mode 100644 index 00000000..4bf34f5d Binary files /dev/null and b/vSLAM/ch8/data/depth/1305031453.473352.png differ diff --git a/vSLAM/ch8/data/depth/1305031453.505218.png b/vSLAM/ch8/data/depth/1305031453.505218.png new file mode 100644 index 00000000..4c2362ec Binary files /dev/null and b/vSLAM/ch8/data/depth/1305031453.505218.png differ diff --git a/vSLAM/ch8/data/depth/1305031453.538301.png b/vSLAM/ch8/data/depth/1305031453.538301.png new file mode 100644 index 00000000..75fe0a26 Binary files /dev/null and b/vSLAM/ch8/data/depth/1305031453.538301.png differ diff --git a/vSLAM/ch8/data/depth/1305031453.574074.png b/vSLAM/ch8/data/depth/1305031453.574074.png new file mode 100644 index 00000000..c9d5b687 Binary files /dev/null and b/vSLAM/ch8/data/depth/1305031453.574074.png differ diff --git a/vSLAM/ch8/data/depth/1305031453.605314.png b/vSLAM/ch8/data/depth/1305031453.605314.png new file mode 100644 index 00000000..b26b835a Binary files /dev/null and b/vSLAM/ch8/data/depth/1305031453.605314.png differ diff --git a/vSLAM/ch8/data/depth/1305031453.636951.png b/vSLAM/ch8/data/depth/1305031453.636951.png new file mode 100644 index 00000000..fb3be1c3 Binary files /dev/null and b/vSLAM/ch8/data/depth/1305031453.636951.png differ diff --git a/vSLAM/ch8/data/groundtruth.txt b/vSLAM/ch8/data/groundtruth.txt new file mode 100644 index 00000000..841b6d40 --- /dev/null +++ b/vSLAM/ch8/data/groundtruth.txt @@ -0,0 +1,2338 @@ +# ground truth trajectory +# file: 'rgbd_dataset_freiburg1_desk.bag' +# timestamp tx ty tz qx qy qz qw +1305031449.7996 1.2334 -0.0113 1.6941 0.7907 0.4393 -0.1770 -0.3879 +1305031449.8096 1.2334 -0.0111 1.6939 0.7911 0.4393 -0.1768 -0.3872 +1305031449.8196 1.2330 -0.0111 1.6937 0.7913 0.4387 -0.1769 -0.3873 +1305031449.8295 1.2328 -0.0110 1.6936 0.7916 0.4384 -0.1768 -0.3872 +1305031449.8396 1.2325 -0.0110 1.6934 0.7919 0.4380 -0.1768 -0.3871 +1305031449.8495 1.2323 -0.0110 1.6934 0.7923 0.4379 -0.1760 -0.3866 +1305031449.8595 1.2321 -0.0109 1.6932 0.7925 0.4374 -0.1758 -0.3868 +1305031449.8696 1.2316 -0.0108 1.6929 0.7926 0.4370 -0.1758 -0.3871 +1305031449.8795 1.2312 -0.0108 1.6927 0.7929 0.4368 -0.1755 -0.3869 +1305031449.8896 1.2307 -0.0106 1.6924 0.7932 0.4368 -0.1750 -0.3865 +1305031449.8994 1.2302 -0.0105 1.6922 0.7935 0.4366 -0.1745 -0.3863 +1305031449.9095 1.2298 -0.0105 1.6920 0.7936 0.4368 -0.1739 -0.3861 +1305031449.9195 1.2292 -0.0104 1.6917 0.7935 0.4368 -0.1735 -0.3865 +1305031449.9295 1.2286 -0.0103 1.6915 0.7934 0.4369 -0.1732 -0.3869 +1305031449.9395 1.2279 -0.0102 1.6914 0.7929 0.4370 -0.1733 -0.3876 +1305031449.9496 1.2273 -0.0101 1.6913 0.7925 0.4372 -0.1733 -0.3883 +1305031449.9595 1.2268 -0.0099 1.6912 0.7921 0.4374 -0.1735 -0.3886 +1305031449.9696 1.2262 -0.0097 1.6911 0.7916 0.4375 -0.1741 -0.3895 +1305031449.9795 1.2254 -0.0094 1.6910 0.7910 0.4379 -0.1744 -0.3901 +1305031449.9895 1.2245 -0.0090 1.6908 0.7901 0.4384 -0.1752 -0.3909 +1305031449.9994 1.2237 -0.0086 1.6905 0.7895 0.4389 -0.1756 -0.3915 +1305031450.0097 1.2229 -0.0081 1.6902 0.7888 0.4398 -0.1758 -0.3918 +1305031450.0195 1.2219 -0.0076 1.6899 0.7881 0.4409 -0.1763 -0.3917 +1305031450.0296 1.2211 -0.0072 1.6896 0.7878 0.4423 -0.1762 -0.3908 +1305031450.0395 1.2203 -0.0066 1.6892 0.7871 0.4441 -0.1764 -0.3901 +1305031450.0495 1.2194 -0.0060 1.6887 0.7863 0.4452 -0.1766 -0.3904 +1305031450.0595 1.2185 -0.0054 1.6881 0.7857 0.4467 -0.1767 -0.3898 +1305031450.0696 1.2177 -0.0048 1.6876 0.7854 0.4484 -0.1771 -0.3881 +1305031450.0795 1.2169 -0.0040 1.6871 0.7851 0.4500 -0.1776 -0.3867 +1305031450.0896 1.2162 -0.0033 1.6865 0.7847 0.4513 -0.1782 -0.3857 +1305031450.0995 1.2154 -0.0023 1.6860 0.7841 0.4529 -0.1791 -0.3847 +1305031450.1096 1.2145 -0.0015 1.6854 0.7834 0.4549 -0.1801 -0.3834 +1305031450.1195 1.2139 -0.0006 1.6848 0.7825 0.4570 -0.1811 -0.3821 +1305031450.1295 1.2132 0.0003 1.6841 0.7814 0.4592 -0.1825 -0.3811 +1305031450.1395 1.2125 0.0013 1.6835 0.7804 0.4611 -0.1842 -0.3800 +1305031450.1496 1.2119 0.0024 1.6828 0.7795 0.4637 -0.1856 -0.3781 +1305031450.1595 1.2112 0.0035 1.6822 0.7781 0.4660 -0.1876 -0.3771 +1305031450.1696 1.2106 0.0046 1.6815 0.7770 0.4681 -0.1897 -0.3757 +1305031450.1796 1.2102 0.0058 1.6808 0.7760 0.4706 -0.1916 -0.3736 +1305031450.1895 1.2096 0.0071 1.6800 0.7749 0.4725 -0.1944 -0.3722 +1305031450.1996 1.2092 0.0086 1.6793 0.7735 0.4745 -0.1971 -0.3710 +1305031450.2096 1.2090 0.0099 1.6786 0.7728 0.4765 -0.1996 -0.3686 +1305031450.2196 1.2086 0.0114 1.6779 0.7714 0.4786 -0.2027 -0.3671 +1305031450.2295 1.2082 0.0130 1.6770 0.7698 0.4807 -0.2059 -0.3660 +1305031450.2395 1.2079 0.0145 1.6762 0.7683 0.4834 -0.2084 -0.3641 +1305031450.2495 1.2076 0.0163 1.6755 0.7659 0.4861 -0.2115 -0.3638 +1305031450.2595 1.2074 0.0180 1.6746 0.7636 0.4894 -0.2143 -0.3626 +1305031450.2695 1.2072 0.0198 1.6738 0.7612 0.4931 -0.2169 -0.3611 +1305031450.2795 1.2069 0.0218 1.6728 0.7583 0.4970 -0.2200 -0.3599 +1305031450.2896 1.2069 0.0234 1.6718 0.7548 0.5003 -0.2236 -0.3605 +1305031450.2995 1.2068 0.0253 1.6708 0.7522 0.5043 -0.2269 -0.3585 +1305031450.3095 1.2070 0.0273 1.6700 0.7499 0.5080 -0.2292 -0.3564 +1305031450.3195 1.2067 0.0295 1.6687 0.7469 0.5116 -0.2333 -0.3548 +1305031450.3295 1.2069 0.0317 1.6677 0.7445 0.5157 -0.2362 -0.3521 +1305031450.3395 1.2070 0.0341 1.6665 0.7423 0.5187 -0.2395 -0.3501 +1305031450.3496 1.2071 0.0365 1.6650 0.7403 0.5220 -0.2429 -0.3471 +1305031450.3595 1.2074 0.0393 1.6636 0.7390 0.5250 -0.2447 -0.3442 +1305031450.3695 1.2080 0.0421 1.6620 0.7380 0.5279 -0.2465 -0.3404 +1305031450.3795 1.2082 0.0449 1.6601 0.7366 0.5303 -0.2491 -0.3379 +1305031450.3895 1.2085 0.0478 1.6586 0.7353 0.5339 -0.2497 -0.3346 +1305031450.3995 1.2087 0.0509 1.6568 0.7332 0.5362 -0.2523 -0.3337 +1305031450.4095 1.2093 0.0540 1.6553 0.7317 0.5396 -0.2526 -0.3311 +1305031450.4195 1.2096 0.0570 1.6535 0.7298 0.5423 -0.2542 -0.3297 +1305031450.4295 1.2101 0.0604 1.6518 0.7276 0.5449 -0.2557 -0.3292 +1305031450.4395 1.2108 0.0635 1.6501 0.7261 0.5473 -0.2568 -0.3275 +1305031450.4495 1.2111 0.0669 1.6484 0.7243 0.5493 -0.2584 -0.3270 +1305031450.4595 1.2119 0.0705 1.6467 0.7230 0.5514 -0.2590 -0.3258 +1305031450.4695 1.2126 0.0740 1.6448 0.7219 0.5522 -0.2603 -0.3258 +1305031450.4796 1.2134 0.0778 1.6431 0.7212 0.5538 -0.2604 -0.3246 +1305031450.4896 1.2141 0.0817 1.6410 0.7205 0.5550 -0.2606 -0.3241 +1305031450.4995 1.2151 0.0856 1.6391 0.7200 0.5559 -0.2603 -0.3238 +1305031450.5094 1.2159 0.0895 1.6370 0.7193 0.5570 -0.2598 -0.3238 +1305031450.5195 1.2167 0.0933 1.6349 0.7182 0.5578 -0.2598 -0.3247 +1305031450.5295 1.2177 0.0976 1.6328 0.7169 0.5585 -0.2601 -0.3263 +1305031450.5395 1.2187 0.1016 1.6310 0.7160 0.5593 -0.2592 -0.3276 +1305031450.5495 1.2195 0.1055 1.6289 0.7141 0.5604 -0.2600 -0.3292 +1305031450.5595 1.2206 0.1094 1.6267 0.7125 0.5611 -0.2603 -0.3313 +1305031450.5695 1.2216 0.1133 1.6244 0.7110 0.5622 -0.2608 -0.3321 +1305031450.5796 1.2228 0.1174 1.6221 0.7102 0.5631 -0.2606 -0.3326 +1305031450.5895 1.2239 0.1215 1.6195 0.7093 0.5633 -0.2613 -0.3337 +1305031450.5995 1.2251 0.1255 1.6170 0.7086 0.5642 -0.2611 -0.3337 +1305031450.6094 1.2261 0.1297 1.6143 0.7083 0.5641 -0.2617 -0.3341 +1305031450.6195 1.2274 0.1339 1.6116 0.7081 0.5641 -0.2618 -0.3343 +1305031450.6295 1.2286 0.1379 1.6088 0.7080 0.5641 -0.2625 -0.3342 +1305031450.6395 1.2298 0.1422 1.6060 0.7079 0.5640 -0.2635 -0.3337 +1305031450.6495 1.2309 0.1462 1.6030 0.7075 0.5642 -0.2647 -0.3333 +1305031450.6595 1.2319 0.1503 1.6000 0.7072 0.5643 -0.2660 -0.3327 +1305031450.6695 1.2330 0.1543 1.5969 0.7072 0.5645 -0.2667 -0.3317 +1305031450.6796 1.2342 0.1585 1.5937 0.7077 0.5647 -0.2671 -0.3301 +1305031450.6895 1.2352 0.1624 1.5904 0.7077 0.5654 -0.2680 -0.3282 +1305031450.6995 1.2363 0.1664 1.5872 0.7082 0.5659 -0.2676 -0.3265 +1305031450.7095 1.2373 0.1706 1.5838 0.7085 0.5663 -0.2682 -0.3247 +1305031450.7195 1.2383 0.1745 1.5804 0.7091 0.5666 -0.2681 -0.3228 +1305031450.7296 1.2392 0.1786 1.5770 0.7098 0.5664 -0.2680 -0.3218 +1305031450.7396 1.2405 0.1827 1.5737 0.7108 0.5660 -0.2677 -0.3203 +1305031450.7495 1.2414 0.1869 1.5705 0.7110 0.5656 -0.2684 -0.3203 +1305031450.7596 1.2422 0.1910 1.5672 0.7110 0.5648 -0.2691 -0.3208 +1305031450.7696 1.2431 0.1950 1.5639 0.7114 0.5644 -0.2689 -0.3210 +1305031450.7795 1.2441 0.1991 1.5608 0.7118 0.5642 -0.2681 -0.3212 +1305031450.7895 1.2450 0.2032 1.5575 0.7122 0.5640 -0.2671 -0.3215 +1305031450.7996 1.2458 0.2072 1.5541 0.7123 0.5638 -0.2664 -0.3220 +1305031450.8094 1.2470 0.2111 1.5510 0.7134 0.5639 -0.2641 -0.3213 +1305031450.8195 1.2479 0.2151 1.5478 0.7143 0.5635 -0.2627 -0.3213 +1305031450.8295 1.2488 0.2191 1.5446 0.7150 0.5627 -0.2615 -0.3222 +1305031450.8396 1.2491 0.2230 1.5413 0.7150 0.5619 -0.2619 -0.3234 +1305031450.8495 1.2502 0.2269 1.5383 0.7161 0.5614 -0.2597 -0.3234 +1305031450.8595 1.2510 0.2307 1.5353 0.7171 0.5613 -0.2578 -0.3230 +1305031450.8695 1.2515 0.2347 1.5322 0.7169 0.5614 -0.2570 -0.3239 +1305031450.8795 1.2528 0.2385 1.5294 0.7185 0.5614 -0.2535 -0.3230 +1305031450.8895 1.2530 0.2425 1.5264 0.7178 0.5619 -0.2535 -0.3238 +1305031450.8996 1.2540 0.2463 1.5237 0.7184 0.5621 -0.2517 -0.3235 +1305031450.9095 1.2545 0.2503 1.5210 0.7177 0.5615 -0.2524 -0.3255 +1305031450.9194 1.2551 0.2543 1.5183 0.7176 0.5606 -0.2533 -0.3266 +1305031450.9295 1.2559 0.2582 1.5159 0.7177 0.5591 -0.2541 -0.3283 +1305031450.9395 1.2563 0.2622 1.5130 0.7173 0.5573 -0.2563 -0.3305 +1305031450.9495 1.2566 0.2662 1.5103 0.7173 0.5560 -0.2577 -0.3315 +1305031450.9595 1.2573 0.2700 1.5075 0.7178 0.5553 -0.2581 -0.3313 +1305031450.9696 1.2575 0.2739 1.5046 0.7179 0.5544 -0.2593 -0.3317 +1305031450.9796 1.2578 0.2777 1.5016 0.7180 0.5541 -0.2600 -0.3315 +1305031450.9895 1.2580 0.2815 1.4985 0.7181 0.5533 -0.2614 -0.3314 +1305031450.9996 1.2581 0.2852 1.4956 0.7182 0.5522 -0.2634 -0.3315 +1305031451.0095 1.2587 0.2887 1.4927 0.7199 0.5512 -0.2627 -0.3300 +1305031451.0195 1.2581 0.2923 1.4895 0.7186 0.5492 -0.2679 -0.3320 +1305031451.0295 1.2579 0.2961 1.4861 0.7184 0.5465 -0.2714 -0.3340 +1305031451.0396 1.2580 0.2994 1.4830 0.7197 0.5453 -0.2722 -0.3325 +1305031451.0495 1.2575 0.3031 1.4794 0.7198 0.5430 -0.2752 -0.3336 +1305031451.0596 1.2572 0.3063 1.4760 0.7211 0.5421 -0.2758 -0.3317 +1305031451.0695 1.2566 0.3095 1.4722 0.7218 0.5406 -0.2780 -0.3309 +1305031451.0795 1.2558 0.3128 1.4684 0.7225 0.5391 -0.2805 -0.3297 +1305031451.0895 1.2550 0.3161 1.4645 0.7233 0.5372 -0.2831 -0.3287 +1305031451.0995 1.2544 0.3193 1.4606 0.7249 0.5355 -0.2847 -0.3268 +1305031451.1096 1.2533 0.3225 1.4565 0.7261 0.5328 -0.2874 -0.3260 +1305031451.1195 1.2524 0.3255 1.4524 0.7281 0.5310 -0.2889 -0.3233 +1305031451.1295 1.2516 0.3285 1.4484 0.7299 0.5292 -0.2900 -0.3212 +1305031451.1396 1.2504 0.3313 1.4442 0.7311 0.5276 -0.2920 -0.3193 +1305031451.1495 1.2493 0.3340 1.4402 0.7322 0.5267 -0.2937 -0.3167 +1305031451.1595 1.2481 0.3365 1.4362 0.7327 0.5261 -0.2960 -0.3144 +1305031451.1696 1.2468 0.3389 1.4322 0.7327 0.5253 -0.2992 -0.3127 +1305031451.1796 1.2453 0.3414 1.4282 0.7327 0.5249 -0.3024 -0.3103 +1305031451.1895 1.2441 0.3438 1.4242 0.7326 0.5256 -0.3043 -0.3072 +1305031451.1995 1.2426 0.3461 1.4199 0.7333 0.5259 -0.3057 -0.3037 +1305031451.2095 1.2413 0.3482 1.4158 0.7345 0.5269 -0.3059 -0.2989 +1305031451.2195 1.2399 0.3505 1.4117 0.7356 0.5274 -0.3061 -0.2950 +1305031451.2295 1.2384 0.3527 1.4075 0.7367 0.5284 -0.3057 -0.2909 +1305031451.2395 1.2372 0.3549 1.4038 0.7374 0.5290 -0.3057 -0.2879 +1305031451.2496 1.2361 0.3571 1.4002 0.7381 0.5298 -0.3050 -0.2855 +1305031451.2596 1.2349 0.3593 1.3967 0.7378 0.5302 -0.3063 -0.2843 +1305031451.2695 1.2335 0.3613 1.3934 0.7374 0.5304 -0.3073 -0.2837 +1305031451.2795 1.2321 0.3635 1.3901 0.7367 0.5315 -0.3080 -0.2828 +1305031451.2895 1.2310 0.3655 1.3870 0.7357 0.5333 -0.3083 -0.2816 +1305031451.2995 1.2296 0.3676 1.3838 0.7339 0.5351 -0.3093 -0.2816 +1305031451.3095 1.2283 0.3697 1.3809 0.7324 0.5378 -0.3097 -0.2800 +1305031451.3195 1.2271 0.3717 1.3778 0.7309 0.5411 -0.3095 -0.2779 +1305031451.3296 1.2257 0.3738 1.3749 0.7296 0.5441 -0.3091 -0.2758 +1305031451.3395 1.2247 0.3761 1.3721 0.7282 0.5472 -0.3094 -0.2730 +1305031451.3495 1.2235 0.3783 1.3694 0.7272 0.5498 -0.3095 -0.2705 +1305031451.3595 1.2222 0.3807 1.3668 0.7253 0.5521 -0.3107 -0.2695 +1305031451.3695 1.2213 0.3830 1.3644 0.7238 0.5549 -0.3114 -0.2669 +1305031451.3796 1.2201 0.3856 1.3622 0.7215 0.5575 -0.3122 -0.2667 +1305031451.3895 1.2191 0.3880 1.3602 0.7193 0.5602 -0.3126 -0.2666 +1305031451.3995 1.2182 0.3907 1.3583 0.7163 0.5641 -0.3125 -0.2664 +1305031451.4096 1.2173 0.3932 1.3567 0.7132 0.5687 -0.3122 -0.2655 +1305031451.4195 1.2162 0.3959 1.3550 0.7092 0.5735 -0.3120 -0.2662 +1305031451.4295 1.2154 0.3987 1.3537 0.7050 0.5786 -0.3113 -0.2669 +1305031451.4395 1.2146 0.4015 1.3524 0.7010 0.5840 -0.3107 -0.2666 +1305031451.4495 1.2137 0.4046 1.3513 0.6967 0.5889 -0.3109 -0.2668 +1305031451.4595 1.2128 0.4077 1.3503 0.6924 0.5934 -0.3115 -0.2673 +1305031451.4695 1.2119 0.4111 1.3494 0.6890 0.5975 -0.3117 -0.2667 +1305031451.4795 1.2113 0.4145 1.3486 0.6865 0.6014 -0.3112 -0.2649 +1305031451.4895 1.2106 0.4182 1.3480 0.6838 0.6047 -0.3118 -0.2636 +1305031451.4996 1.2098 0.4219 1.3477 0.6808 0.6073 -0.3137 -0.2632 +1305031451.5096 1.2090 0.4255 1.3476 0.6770 0.6101 -0.3164 -0.2634 +1305031451.5196 1.2078 0.4292 1.3475 0.6722 0.6132 -0.3206 -0.2634 +1305031451.5295 1.2073 0.4329 1.3478 0.6682 0.6180 -0.3216 -0.2610 +1305031451.5395 1.2066 0.4368 1.3482 0.6637 0.6228 -0.3238 -0.2584 +1305031451.5495 1.2060 0.4407 1.3486 0.6596 0.6268 -0.3261 -0.2563 +1305031451.5595 1.2055 0.4447 1.3492 0.6557 0.6302 -0.3288 -0.2545 +1305031451.5695 1.2049 0.4491 1.3500 0.6521 0.6325 -0.3324 -0.2534 +1305031451.5795 1.2042 0.4536 1.3508 0.6500 0.6343 -0.3342 -0.2518 +1305031451.5895 1.2035 0.4584 1.3516 0.6479 0.6362 -0.3360 -0.2500 +1305031451.5995 1.2030 0.4633 1.3527 0.6472 0.6378 -0.3364 -0.2473 +1305031451.6095 1.2023 0.4683 1.3537 0.6476 0.6392 -0.3357 -0.2436 +1305031451.6195 1.2013 0.4733 1.3547 0.6476 0.6394 -0.3367 -0.2419 +1305031451.6296 1.2005 0.4784 1.3560 0.6477 0.6397 -0.3373 -0.2399 +1305031451.6395 1.1998 0.4836 1.3574 0.6482 0.6397 -0.3375 -0.2382 +1305031451.6496 1.1990 0.4888 1.3589 0.6484 0.6396 -0.3382 -0.2372 +1305031451.6595 1.1983 0.4940 1.3605 0.6477 0.6397 -0.3393 -0.2368 +1305031451.6695 1.1976 0.4992 1.3624 0.6468 0.6397 -0.3407 -0.2372 +1305031451.6796 1.1970 0.5045 1.3644 0.6458 0.6400 -0.3416 -0.2380 +1305031451.6895 1.1960 0.5095 1.3662 0.6436 0.6385 -0.3464 -0.2409 +1305031451.6995 1.1957 0.5147 1.3684 0.6433 0.6393 -0.3458 -0.2405 +1305031451.7095 1.1951 0.5199 1.3706 0.6428 0.6382 -0.3479 -0.2419 +1305031451.7195 1.1946 0.5251 1.3725 0.6433 0.6375 -0.3483 -0.2416 +1305031451.7296 1.1943 0.5301 1.3748 0.6437 0.6368 -0.3488 -0.2418 +1305031451.7395 1.1937 0.5353 1.3771 0.6446 0.6355 -0.3489 -0.2427 +1305031451.7496 1.1926 0.5404 1.3794 0.6448 0.6335 -0.3510 -0.2443 +1305031451.7596 1.1922 0.5453 1.3818 0.6462 0.6318 -0.3513 -0.2446 +1305031451.7695 1.1918 0.5502 1.3843 0.6475 0.6303 -0.3514 -0.2449 +1305031451.7795 1.1913 0.5550 1.3868 0.6485 0.6284 -0.3522 -0.2460 +1305031451.7895 1.1910 0.5598 1.3894 0.6502 0.6270 -0.3519 -0.2456 +1305031451.7995 1.1908 0.5642 1.3917 0.6521 0.6249 -0.3520 -0.2459 +1305031451.8095 1.1906 0.5687 1.3945 0.6535 0.6231 -0.3519 -0.2467 +1305031451.8195 1.1900 0.5733 1.3971 0.6545 0.6208 -0.3528 -0.2485 +1305031451.8295 1.1896 0.5779 1.3999 0.6558 0.6185 -0.3533 -0.2502 +1305031451.8396 1.1894 0.5822 1.4030 0.6567 0.6169 -0.3532 -0.2520 +1305031451.8495 1.1889 0.5862 1.4057 0.6575 0.6148 -0.3541 -0.2535 +1305031451.8596 1.1885 0.5903 1.4086 0.6583 0.6130 -0.3546 -0.2550 +1305031451.8695 1.1883 0.5942 1.4115 0.6596 0.6118 -0.3536 -0.2560 +1305031451.8796 1.1878 0.5981 1.4144 0.6608 0.6102 -0.3528 -0.2580 +1305031451.8895 1.1875 0.6019 1.4174 0.6620 0.6086 -0.3518 -0.2601 +1305031451.8995 1.1872 0.6054 1.4204 0.6629 0.6071 -0.3504 -0.2630 +1305031451.9095 1.1871 0.6087 1.4236 0.6637 0.6065 -0.3484 -0.2651 +1305031451.9195 1.1864 0.6123 1.4268 0.6639 0.6045 -0.3480 -0.2695 +1305031451.9295 1.1860 0.6155 1.4298 0.6651 0.6027 -0.3467 -0.2723 +1305031451.9395 1.1858 0.6187 1.4328 0.6669 0.6012 -0.3443 -0.2743 +1305031451.9496 1.1855 0.6220 1.4357 0.6689 0.5997 -0.3416 -0.2762 +1305031451.9595 1.1861 0.6251 1.4387 0.6731 0.5976 -0.3360 -0.2774 +1305031451.9695 1.1860 0.6282 1.4415 0.6760 0.5962 -0.3318 -0.2785 +1305031451.9794 1.1857 0.6315 1.4441 0.6793 0.5958 -0.3267 -0.2773 +1305031451.9895 1.1850 0.6345 1.4468 0.6821 0.5940 -0.3237 -0.2777 +1305031451.9995 1.1849 0.6377 1.4494 0.6868 0.5916 -0.3189 -0.2769 +1305031452.0096 1.1846 0.6408 1.4521 0.6912 0.5897 -0.3141 -0.2752 +1305031452.0195 1.1844 0.6441 1.4548 0.6951 0.5882 -0.3103 -0.2731 +1305031452.0296 1.1847 0.6473 1.4574 0.7001 0.5864 -0.3049 -0.2703 +1305031452.0395 1.1843 0.6507 1.4602 0.7036 0.5850 -0.3015 -0.2681 +1305031452.0495 1.1841 0.6540 1.4628 0.7069 0.5824 -0.2996 -0.2670 +1305031452.0595 1.1839 0.6574 1.4654 0.7105 0.5798 -0.2976 -0.2654 +1305031452.0695 1.1837 0.6609 1.4681 0.7139 0.5780 -0.2952 -0.2629 +1305031452.0795 1.1840 0.6644 1.4711 0.7171 0.5759 -0.2931 -0.2611 +1305031452.0895 1.1840 0.6683 1.4738 0.7195 0.5732 -0.2931 -0.2606 +1305031452.0994 1.1841 0.6720 1.4766 0.7220 0.5702 -0.2932 -0.2602 +1305031452.1095 1.1842 0.6756 1.4795 0.7246 0.5681 -0.2918 -0.2590 +1305031452.1195 1.1846 0.6794 1.4824 0.7273 0.5654 -0.2902 -0.2590 +1305031452.1295 1.1846 0.6831 1.4853 0.7296 0.5620 -0.2899 -0.2605 +1305031452.1395 1.1850 0.6870 1.4883 0.7316 0.5596 -0.2888 -0.2611 +1305031452.1495 1.1855 0.6908 1.4912 0.7339 0.5569 -0.2869 -0.2625 +1305031452.1595 1.1856 0.6948 1.4941 0.7354 0.5541 -0.2861 -0.2652 +1305031452.1695 1.1859 0.6986 1.4969 0.7369 0.5509 -0.2853 -0.2685 +1305031452.1795 1.1863 0.7027 1.4996 0.7382 0.5490 -0.2834 -0.2710 +1305031452.1894 1.1870 0.7066 1.5024 0.7403 0.5470 -0.2803 -0.2722 +1305031452.1995 1.1872 0.7106 1.5049 0.7417 0.5456 -0.2776 -0.2741 +1305031452.2097 1.1879 0.7147 1.5075 0.7429 0.5443 -0.2752 -0.2758 +1305031452.2195 1.1883 0.7184 1.5102 0.7447 0.5422 -0.2726 -0.2776 +1305031452.2295 1.1888 0.7226 1.5129 0.7462 0.5407 -0.2702 -0.2790 +1305031452.2395 1.1895 0.7265 1.5153 0.7476 0.5391 -0.2687 -0.2798 +1305031452.2495 1.1897 0.7305 1.5175 0.7484 0.5367 -0.2683 -0.2824 +1305031452.2595 1.1898 0.7345 1.5199 0.7488 0.5360 -0.2680 -0.2830 +1305031452.2694 1.1902 0.7384 1.5223 0.7499 0.5347 -0.2669 -0.2839 +1305031452.2795 1.1905 0.7421 1.5244 0.7501 0.5341 -0.2667 -0.2847 +1305031452.2895 1.1906 0.7459 1.5264 0.7501 0.5341 -0.2661 -0.2852 +1305031452.2995 1.1910 0.7495 1.5286 0.7504 0.5344 -0.2649 -0.2849 +1305031452.3095 1.1911 0.7535 1.5306 0.7501 0.5346 -0.2643 -0.2857 +1305031452.3195 1.1911 0.7571 1.5325 0.7495 0.5356 -0.2641 -0.2858 +1305031452.3295 1.1912 0.7607 1.5346 0.7496 0.5366 -0.2626 -0.2848 +1305031452.3395 1.1914 0.7646 1.5364 0.7502 0.5365 -0.2615 -0.2846 +1305031452.3496 1.1916 0.7686 1.5382 0.7509 0.5357 -0.2612 -0.2847 +1305031452.3596 1.1913 0.7729 1.5399 0.7513 0.5340 -0.2613 -0.2866 +1305031452.3696 1.1919 0.7771 1.5417 0.7532 0.5327 -0.2590 -0.2862 +1305031452.3795 1.1920 0.7814 1.5431 0.7549 0.5302 -0.2582 -0.2867 +1305031452.3895 1.1921 0.7861 1.5446 0.7576 0.5272 -0.2566 -0.2869 +1305031452.3995 1.1918 0.7909 1.5458 0.7599 0.5238 -0.2559 -0.2877 +1305031452.4095 1.1921 0.7955 1.5471 0.7635 0.5191 -0.2545 -0.2878 +1305031452.4195 1.1921 0.8001 1.5479 0.7675 0.5135 -0.2537 -0.2880 +1305031452.4294 1.1921 0.8051 1.5491 0.7706 0.5079 -0.2535 -0.2899 +1305031452.4395 1.1921 0.8103 1.5504 0.7739 0.5022 -0.2525 -0.2917 +1305031452.4495 1.1926 0.8148 1.5514 0.7774 0.4970 -0.2514 -0.2924 +1305031452.4595 1.1929 0.8194 1.5523 0.7805 0.4922 -0.2502 -0.2931 +1305031452.4695 1.1935 0.8237 1.5531 0.7834 0.4876 -0.2493 -0.2941 +1305031452.4795 1.1942 0.8282 1.5540 0.7865 0.4837 -0.2469 -0.2942 +1305031452.4895 1.1946 0.8323 1.5546 0.7887 0.4798 -0.2455 -0.2958 +1305031452.4995 1.1954 0.8365 1.5553 0.7914 0.4758 -0.2432 -0.2970 +1305031452.5095 1.1961 0.8405 1.5559 0.7937 0.4724 -0.2412 -0.2980 +1305031452.5195 1.1971 0.8446 1.5565 0.7961 0.4683 -0.2392 -0.2994 +1305031452.5294 1.1979 0.8486 1.5570 0.7991 0.4652 -0.2361 -0.2988 +1305031452.5395 1.1987 0.8526 1.5576 0.8010 0.4618 -0.2346 -0.3002 +1305031452.5495 1.1998 0.8563 1.5580 0.8031 0.4577 -0.2329 -0.3023 +1305031452.5594 1.1997 0.8603 1.5582 0.8030 0.4533 -0.2338 -0.3084 +1305031452.5694 1.2004 0.8639 1.5584 0.8040 0.4501 -0.2329 -0.3109 +1305031452.5795 1.2016 0.8670 1.5588 0.8059 0.4476 -0.2300 -0.3120 +1305031452.5895 1.2024 0.8702 1.5590 0.8070 0.4462 -0.2274 -0.3129 +1305031452.5994 1.2033 0.8734 1.5590 0.8081 0.4451 -0.2252 -0.3132 +1305031452.6095 1.2042 0.8764 1.5589 0.8092 0.4426 -0.2232 -0.3153 +1305031452.6195 1.2052 0.8794 1.5589 0.8108 0.4403 -0.2206 -0.3163 +1305031452.6294 1.2061 0.8824 1.5587 0.8119 0.4378 -0.2189 -0.3183 +1305031452.6395 1.2069 0.8853 1.5582 0.8134 0.4341 -0.2179 -0.3201 +1305031452.6495 1.2080 0.8881 1.5578 0.8151 0.4309 -0.2165 -0.3211 +1305031452.6595 1.2087 0.8907 1.5572 0.8168 0.4280 -0.2153 -0.3214 +1305031452.6694 1.2097 0.8933 1.5564 0.8189 0.4251 -0.2138 -0.3210 +1305031452.6795 1.2106 0.8958 1.5557 0.8207 0.4216 -0.2125 -0.3218 +1305031452.6895 1.2116 0.8983 1.5550 0.8229 0.4180 -0.2105 -0.3222 +1305031452.6995 1.2127 0.9006 1.5542 0.8252 0.4140 -0.2088 -0.3226 +1305031452.7095 1.2136 0.9030 1.5533 0.8273 0.4095 -0.2078 -0.3236 +1305031452.7195 1.2147 0.9051 1.5524 0.8295 0.4041 -0.2070 -0.3252 +1305031452.7295 1.2157 0.9072 1.5515 0.8320 0.3993 -0.2061 -0.3254 +1305031452.7395 1.2168 0.9089 1.5501 0.8345 0.3936 -0.2064 -0.3258 +1305031452.7495 1.2179 0.9105 1.5489 0.8373 0.3891 -0.2057 -0.3245 +1305031452.7595 1.2189 0.9121 1.5475 0.8394 0.3845 -0.2057 -0.3244 +1305031452.7695 1.2200 0.9134 1.5461 0.8421 0.3805 -0.2049 -0.3226 +1305031452.7796 1.2213 0.9145 1.5446 0.8454 0.3760 -0.2030 -0.3205 +1305031452.7895 1.2223 0.9157 1.5433 0.8475 0.3710 -0.2026 -0.3211 +1305031452.7995 1.2234 0.9168 1.5419 0.8495 0.3656 -0.2022 -0.3222 +1305031452.8094 1.2248 0.9175 1.5408 0.8521 0.3603 -0.2016 -0.3217 +1305031452.8195 1.2260 0.9181 1.5396 0.8544 0.3552 -0.2008 -0.3218 +1305031452.8294 1.2271 0.9186 1.5381 0.8559 0.3490 -0.2016 -0.3239 +1305031452.8395 1.2287 0.9185 1.5374 0.8584 0.3439 -0.2002 -0.3238 +1305031452.8495 1.2298 0.9187 1.5362 0.8595 0.3388 -0.2007 -0.3259 +1305031452.8595 1.2311 0.9185 1.5350 0.8609 0.3349 -0.2002 -0.3264 +1305031452.8694 1.2325 0.9180 1.5338 0.8630 0.3310 -0.1994 -0.3255 +1305031452.8795 1.2335 0.9177 1.5327 0.8639 0.3285 -0.1993 -0.3257 +1305031452.8895 1.2348 0.9170 1.5316 0.8656 0.3264 -0.1978 -0.3242 +1305031452.8995 1.2360 0.9164 1.5305 0.8666 0.3256 -0.1964 -0.3233 +1305031452.9095 1.2370 0.9156 1.5295 0.8674 0.3239 -0.1952 -0.3233 +1305031452.9295 1.2388 0.9137 1.5275 0.8677 0.3225 -0.1945 -0.3245 +1305031452.9394 1.2401 0.9127 1.5267 0.8682 0.3218 -0.1933 -0.3245 +1305031452.9495 1.2410 0.9114 1.5258 0.8682 0.3215 -0.1928 -0.3251 +1305031452.9595 1.2420 0.9103 1.5252 0.8679 0.3216 -0.1917 -0.3266 +1305031452.9695 1.2427 0.9092 1.5245 0.8672 0.3210 -0.1910 -0.3294 +1305031452.9795 1.2440 0.9078 1.5238 0.8674 0.3202 -0.1896 -0.3303 +1305031452.9895 1.2450 0.9068 1.5231 0.8669 0.3186 -0.1880 -0.3341 +1305031452.9995 1.2464 0.9054 1.5226 0.8675 0.3172 -0.1853 -0.3353 +1305031453.0095 1.2477 0.9040 1.5220 0.8679 0.3152 -0.1824 -0.3377 +1305031453.0195 1.2492 0.9027 1.5215 0.8687 0.3130 -0.1793 -0.3394 +1305031453.0295 1.2503 0.9017 1.5208 0.8690 0.3108 -0.1765 -0.3422 +1305031453.0395 1.2516 0.9005 1.5202 0.8697 0.3090 -0.1734 -0.3437 +1305031453.0496 1.2530 0.8991 1.5194 0.8703 0.3064 -0.1702 -0.3460 +1305031453.0595 1.2543 0.8978 1.5190 0.8711 0.3052 -0.1666 -0.3468 +1305031453.0695 1.2557 0.8966 1.5184 0.8715 0.3032 -0.1633 -0.3491 +1305031453.0795 1.2572 0.8952 1.5181 0.8720 0.3020 -0.1597 -0.3505 +1305031453.0894 1.2588 0.8937 1.5175 0.8724 0.2990 -0.1566 -0.3537 +1305031453.0996 1.2602 0.8925 1.5172 0.8729 0.2976 -0.1530 -0.3551 +1305031453.1094 1.2617 0.8914 1.5165 0.8726 0.2957 -0.1500 -0.3587 +1305031453.1195 1.2630 0.8898 1.5162 0.8734 0.2942 -0.1471 -0.3591 +1305031453.1294 1.2646 0.8885 1.5157 0.8735 0.2926 -0.1440 -0.3615 +1305031453.1395 1.2661 0.8870 1.5153 0.8742 0.2916 -0.1407 -0.3620 +1305031453.1495 1.2679 0.8853 1.5147 0.8748 0.2905 -0.1371 -0.3628 +1305031453.1606 1.2693 0.8839 1.5144 0.8749 0.2893 -0.1343 -0.3644 +1305031453.1695 1.2706 0.8827 1.5140 0.8745 0.2879 -0.1314 -0.3676 +1305031453.1795 1.2723 0.8811 1.5138 0.8746 0.2864 -0.1281 -0.3696 +1305031453.1895 1.2742 0.8795 1.5136 0.8752 0.2850 -0.1243 -0.3707 +1305031453.1995 1.2757 0.8782 1.5134 0.8750 0.2828 -0.1217 -0.3736 +1305031453.2095 1.2775 0.8767 1.5132 0.8748 0.2812 -0.1192 -0.3762 +1305031453.2195 1.2794 0.8749 1.5133 0.8755 0.2798 -0.1162 -0.3765 +1305031453.2295 1.2812 0.8735 1.5132 0.8757 0.2774 -0.1136 -0.3785 +1305031453.2395 1.2830 0.8720 1.5133 0.8765 0.2757 -0.1113 -0.3786 +1305031453.2495 1.2851 0.8702 1.5131 0.8772 0.2736 -0.1092 -0.3790 +1305031453.2595 1.2871 0.8687 1.5134 0.8784 0.2712 -0.1064 -0.3789 +1305031453.2695 1.2892 0.8669 1.5137 0.8791 0.2680 -0.1044 -0.3800 +1305031453.2795 1.2916 0.8654 1.5140 0.8796 0.2647 -0.1026 -0.3817 +1305031453.2895 1.2940 0.8637 1.5146 0.8801 0.2615 -0.1013 -0.3830 +1305031453.2995 1.2964 0.8622 1.5152 0.8804 0.2576 -0.0995 -0.3857 +1305031453.3095 1.2989 0.8607 1.5157 0.8802 0.2540 -0.0978 -0.3889 +1305031453.3195 1.3013 0.8587 1.5166 0.8809 0.2501 -0.0959 -0.3902 +1305031453.3295 1.3038 0.8567 1.5171 0.8817 0.2466 -0.0941 -0.3912 +1305031453.3395 1.3063 0.8548 1.5175 0.8823 0.2431 -0.0923 -0.3924 +1305031453.3495 1.3088 0.8528 1.5181 0.8837 0.2395 -0.0910 -0.3918 +1305031453.3595 1.3112 0.8507 1.5186 0.8851 0.2362 -0.0898 -0.3909 +1305031453.3695 1.3137 0.8486 1.5192 0.8862 0.2326 -0.0893 -0.3906 +1305031453.3795 1.3161 0.8465 1.5198 0.8866 0.2293 -0.0894 -0.3917 +1305031453.3894 1.3190 0.8446 1.5203 0.8871 0.2258 -0.0894 -0.3926 +1305031453.3995 1.3212 0.8419 1.5212 0.8885 0.2232 -0.0896 -0.3908 +1305031453.4095 1.3237 0.8399 1.5217 0.8883 0.2196 -0.0905 -0.3930 +1305031453.4195 1.3263 0.8375 1.5226 0.8884 0.2171 -0.0899 -0.3943 +1305031453.4295 1.3291 0.8350 1.5236 0.8889 0.2134 -0.0896 -0.3955 +1305031453.4395 1.3320 0.8325 1.5244 0.8892 0.2106 -0.0890 -0.3963 +1305031453.4495 1.3343 0.8301 1.5255 0.8892 0.2071 -0.0893 -0.3982 +1305031453.4595 1.3370 0.8274 1.5265 0.8893 0.2037 -0.0885 -0.3998 +1305031453.4695 1.3399 0.8246 1.5276 0.8899 0.2000 -0.0879 -0.4005 +1305031453.4795 1.3427 0.8218 1.5285 0.8899 0.1967 -0.0880 -0.4020 +1305031453.4895 1.3454 0.8190 1.5298 0.8900 0.1933 -0.0877 -0.4036 +1305031453.4995 1.3480 0.8158 1.5311 0.8900 0.1906 -0.0879 -0.4048 +1305031453.5095 1.3506 0.8129 1.5323 0.8890 0.1877 -0.0886 -0.4082 +1305031453.5195 1.3531 0.8097 1.5335 0.8887 0.1852 -0.0888 -0.4099 +1305031453.5295 1.3555 0.8063 1.5349 0.8886 0.1824 -0.0894 -0.4112 +1305031453.5395 1.3579 0.8028 1.5362 0.8882 0.1804 -0.0900 -0.4129 +1305031453.5494 1.3602 0.7993 1.5376 0.8875 0.1786 -0.0907 -0.4149 +1305031453.5595 1.3627 0.7957 1.5391 0.8865 0.1763 -0.0915 -0.4180 +1305031453.5695 1.3650 0.7919 1.5405 0.8863 0.1751 -0.0914 -0.4188 +1305031453.5795 1.3671 0.7882 1.5420 0.8858 0.1733 -0.0919 -0.4205 +1305031453.5899 1.3693 0.7843 1.5435 0.8853 0.1717 -0.0922 -0.4222 +1305031453.5995 1.3712 0.7805 1.5448 0.8838 0.1699 -0.0932 -0.4258 +1305031453.6095 1.3731 0.7760 1.5462 0.8842 0.1692 -0.0933 -0.4252 +1305031453.6195 1.3745 0.7721 1.5475 0.8826 0.1686 -0.0948 -0.4285 +1305031453.6295 1.3762 0.7680 1.5488 0.8813 0.1690 -0.0962 -0.4308 +1305031453.6395 1.3775 0.7631 1.5502 0.8805 0.1700 -0.0973 -0.4317 +1305031453.6495 1.3788 0.7586 1.5514 0.8790 0.1709 -0.0986 -0.4342 +1305031453.6595 1.3800 0.7538 1.5526 0.8781 0.1722 -0.0999 -0.4352 +1305031453.6695 1.3809 0.7491 1.5537 0.8761 0.1741 -0.1017 -0.4380 +1305031453.6794 1.3820 0.7442 1.5551 0.8751 0.1752 -0.1031 -0.4391 +1305031453.6895 1.3830 0.7390 1.5562 0.8749 0.1765 -0.1038 -0.4388 +1305031453.6995 1.3837 0.7342 1.5573 0.8734 0.1781 -0.1052 -0.4408 +1305031453.7095 1.3842 0.7291 1.5582 0.8725 0.1799 -0.1064 -0.4417 +1305031453.7202 1.3848 0.7242 1.5592 0.8710 0.1825 -0.1076 -0.4433 +1305031453.7295 1.3850 0.7191 1.5602 0.8698 0.1851 -0.1094 -0.4441 +1305031453.7395 1.3856 0.7136 1.5613 0.8694 0.1886 -0.1103 -0.4432 +1305031453.7495 1.3856 0.7085 1.5623 0.8677 0.1917 -0.1124 -0.4446 +1305031453.7595 1.3859 0.7035 1.5632 0.8661 0.1950 -0.1146 -0.4457 +1305031453.7695 1.3859 0.6985 1.5641 0.8645 0.1975 -0.1167 -0.4472 +1305031453.7795 1.3858 0.6935 1.5652 0.8632 0.2007 -0.1185 -0.4479 +1305031453.7895 1.3858 0.6887 1.5660 0.8618 0.2031 -0.1197 -0.4491 +1305031453.7995 1.3855 0.6836 1.5670 0.8614 0.2056 -0.1209 -0.4484 +1305031453.8095 1.3853 0.6786 1.5677 0.8602 0.2074 -0.1218 -0.4496 +1305031453.8195 1.3846 0.6739 1.5685 0.8588 0.2106 -0.1238 -0.4503 +1305031453.8295 1.3841 0.6691 1.5694 0.8574 0.2137 -0.1260 -0.4510 +1305031453.8394 1.3831 0.6643 1.5701 0.8563 0.2171 -0.1284 -0.4507 +1305031453.8494 1.3823 0.6595 1.5708 0.8553 0.2209 -0.1313 -0.4499 +1305031453.8595 1.3814 0.6549 1.5717 0.8544 0.2245 -0.1344 -0.4490 +1305031453.8694 1.3807 0.6504 1.5724 0.8536 0.2287 -0.1378 -0.4474 +1305031453.8794 1.3794 0.6459 1.5731 0.8526 0.2323 -0.1410 -0.4464 +1305031453.8894 1.3781 0.6416 1.5737 0.8515 0.2357 -0.1449 -0.4453 +1305031453.8995 1.3769 0.6373 1.5744 0.8513 0.2391 -0.1487 -0.4428 +1305031453.9095 1.3756 0.6329 1.5751 0.8509 0.2427 -0.1529 -0.4402 +1305031453.9195 1.3738 0.6289 1.5755 0.8498 0.2456 -0.1576 -0.4389 +1305031453.9295 1.3720 0.6246 1.5762 0.8491 0.2489 -0.1616 -0.4370 +1305031453.9394 1.3703 0.6207 1.5769 0.8484 0.2532 -0.1645 -0.4349 +1305031453.9495 1.3685 0.6168 1.5776 0.8474 0.2572 -0.1668 -0.4336 +1305031453.9597 1.3666 0.6128 1.5783 0.8466 0.2621 -0.1685 -0.4315 +1305031453.9695 1.3647 0.6089 1.5788 0.8460 0.2668 -0.1699 -0.4292 +1305031453.9795 1.3620 0.6050 1.5796 0.8448 0.2709 -0.1705 -0.4288 +1305031453.9895 1.3600 0.6014 1.5803 0.8434 0.2745 -0.1722 -0.4287 +1305031453.9995 1.3579 0.5976 1.5809 0.8418 0.2780 -0.1745 -0.4286 +1305031454.0096 1.3559 0.5939 1.5813 0.8400 0.2812 -0.1769 -0.4289 +1305031454.0195 1.3536 0.5904 1.5818 0.8378 0.2846 -0.1796 -0.4300 +1305031454.0295 1.3515 0.5868 1.5823 0.8369 0.2887 -0.1810 -0.4283 +1305031454.0395 1.3491 0.5834 1.5826 0.8348 0.2931 -0.1832 -0.4285 +1305031454.0495 1.3464 0.5802 1.5828 0.8330 0.2969 -0.1845 -0.4289 +1305031454.0594 1.3436 0.5770 1.5831 0.8307 0.3023 -0.1863 -0.4288 +1305031454.0695 1.3411 0.5737 1.5832 0.8287 0.3070 -0.1876 -0.4288 +1305031454.0794 1.3382 0.5708 1.5833 0.8271 0.3115 -0.1885 -0.4282 +1305031454.0894 1.3354 0.5676 1.5837 0.8246 0.3163 -0.1899 -0.4287 +1305031454.0995 1.3326 0.5643 1.5840 0.8226 0.3211 -0.1913 -0.4286 +1305031454.1095 1.3300 0.5608 1.5844 0.8207 0.3269 -0.1931 -0.4270 +1305031454.1195 1.3271 0.5578 1.5847 0.8178 0.3319 -0.1958 -0.4274 +1305031454.1295 1.3241 0.5547 1.5847 0.8152 0.3365 -0.1986 -0.4275 +1305031454.1394 1.3211 0.5518 1.5848 0.8133 0.3414 -0.2003 -0.4264 +1305031454.1495 1.3184 0.5488 1.5849 0.8119 0.3466 -0.2020 -0.4242 +1305031454.1595 1.3153 0.5461 1.5848 0.8095 0.3512 -0.2051 -0.4235 +1305031454.1694 1.3125 0.5429 1.5847 0.8079 0.3564 -0.2071 -0.4212 +1305031454.1795 1.3097 0.5400 1.5848 0.8057 0.3622 -0.2096 -0.4192 +1305031454.1895 1.3065 0.5372 1.5847 0.8029 0.3678 -0.2123 -0.4183 +1305031454.1995 1.3036 0.5343 1.5847 0.7996 0.3742 -0.2152 -0.4175 +1305031454.2095 1.3008 0.5314 1.5849 0.7967 0.3804 -0.2168 -0.4166 +1305031454.2195 1.2981 0.5285 1.5849 0.7931 0.3864 -0.2192 -0.4166 +1305031454.2295 1.2955 0.5257 1.5851 0.7890 0.3923 -0.2219 -0.4176 +1305031454.2395 1.2933 0.5227 1.5850 0.7865 0.3968 -0.2227 -0.4176 +1305031454.2495 1.2908 0.5201 1.5850 0.7837 0.4010 -0.2244 -0.4179 +1305031454.2595 1.2885 0.5176 1.5849 0.7816 0.4047 -0.2249 -0.4179 +1305031454.2695 1.2862 0.5152 1.5848 0.7802 0.4082 -0.2251 -0.4171 +1305031454.2795 1.2839 0.5127 1.5843 0.7794 0.4123 -0.2245 -0.4150 +1305031454.2895 1.2814 0.5103 1.5841 0.7779 0.4161 -0.2246 -0.4139 +1305031454.2995 1.2790 0.5078 1.5838 0.7756 0.4206 -0.2249 -0.4134 +1305031454.3096 1.2769 0.5052 1.5836 0.7726 0.4260 -0.2258 -0.4130 +1305031454.3195 1.2746 0.5028 1.5834 0.7687 0.4314 -0.2274 -0.4139 +1305031454.3295 1.2726 0.5003 1.5832 0.7648 0.4366 -0.2292 -0.4146 +1305031454.3395 1.2707 0.4978 1.5832 0.7614 0.4409 -0.2307 -0.4155 +1305031454.3495 1.2689 0.4955 1.5829 0.7581 0.4448 -0.2323 -0.4164 +1305031454.3595 1.2669 0.4933 1.5825 0.7554 0.4480 -0.2338 -0.4172 +1305031454.3695 1.2648 0.4910 1.5819 0.7531 0.4504 -0.2353 -0.4178 +1305031454.3795 1.2635 0.4888 1.5818 0.7516 0.4554 -0.2342 -0.4158 +1305031454.3896 1.2619 0.4866 1.5814 0.7493 0.4596 -0.2342 -0.4152 +1305031454.3995 1.2600 0.4842 1.5809 0.7460 0.4638 -0.2359 -0.4157 +1305031454.4095 1.2586 0.4818 1.5802 0.7426 0.4695 -0.2374 -0.4144 +1305031454.4195 1.2571 0.4794 1.5797 0.7389 0.4749 -0.2393 -0.4138 +1305031454.4295 1.2558 0.4771 1.5791 0.7350 0.4798 -0.2415 -0.4139 +1305031454.4395 1.2544 0.4750 1.5784 0.7311 0.4839 -0.2435 -0.4147 +1305031454.4495 1.2534 0.4726 1.5778 0.7285 0.4878 -0.2437 -0.4147 +1305031454.4595 1.2523 0.4703 1.5770 0.7261 0.4916 -0.2432 -0.4146 +1305031454.4695 1.2513 0.4679 1.5761 0.7233 0.4957 -0.2426 -0.4151 +1305031454.4795 1.2507 0.4657 1.5753 0.7207 0.5002 -0.2413 -0.4150 +1305031454.4895 1.2498 0.4632 1.5744 0.7173 0.5053 -0.2407 -0.4150 +1305031454.4995 1.2492 0.4609 1.5733 0.7134 0.5100 -0.2408 -0.4159 +1305031454.5095 1.2486 0.4586 1.5722 0.7109 0.5147 -0.2403 -0.4147 +1305031454.5195 1.2483 0.4564 1.5710 0.7087 0.5188 -0.2399 -0.4136 +1305031454.5295 1.2482 0.4542 1.5701 0.7073 0.5227 -0.2389 -0.4117 +1305031454.5395 1.2478 0.4521 1.5687 0.7053 0.5258 -0.2389 -0.4110 +1305031454.5495 1.2477 0.4500 1.5674 0.7031 0.5300 -0.2388 -0.4095 +1305031454.5595 1.2478 0.4479 1.5663 0.7009 0.5353 -0.2377 -0.4070 +1305031454.5695 1.2477 0.4459 1.5650 0.6976 0.5408 -0.2379 -0.4053 +1305031454.5795 1.2481 0.4437 1.5636 0.6944 0.5465 -0.2379 -0.4031 +1305031454.5895 1.2485 0.4417 1.5620 0.6898 0.5517 -0.2399 -0.4027 +1305031454.5995 1.2492 0.4397 1.5605 0.6869 0.5564 -0.2411 -0.4006 +1305031454.6096 1.2495 0.4380 1.5593 0.6825 0.5617 -0.2431 -0.3995 +1305031454.6194 1.2503 0.4362 1.5579 0.6800 0.5657 -0.2448 -0.3971 +1305031454.6295 1.2509 0.4348 1.5564 0.6774 0.5685 -0.2475 -0.3958 +1305031454.6394 1.2521 0.4334 1.5548 0.6761 0.5720 -0.2488 -0.3921 +1305031454.6495 1.2529 0.4322 1.5531 0.6744 0.5745 -0.2513 -0.3898 +1305031454.6595 1.2541 0.4309 1.5515 0.6734 0.5776 -0.2530 -0.3860 +1305031454.6695 1.2552 0.4296 1.5499 0.6715 0.5807 -0.2556 -0.3827 +1305031454.6795 1.2565 0.4284 1.5482 0.6693 0.5842 -0.2584 -0.3795 +1305031454.6895 1.2577 0.4272 1.5464 0.6663 0.5872 -0.2622 -0.3775 +1305031454.6995 1.2596 0.4262 1.5450 0.6646 0.5907 -0.2633 -0.3742 +1305031454.7095 1.2613 0.4251 1.5434 0.6628 0.5930 -0.2662 -0.3719 +1305031454.7195 1.2630 0.4243 1.5419 0.6616 0.5942 -0.2689 -0.3701 +1305031454.7295 1.2647 0.4236 1.5403 0.6612 0.5947 -0.2713 -0.3682 +1305031454.7394 1.2665 0.4229 1.5387 0.6619 0.5941 -0.2734 -0.3665 +1305031454.7495 1.2686 0.4224 1.5371 0.6636 0.5935 -0.2738 -0.3638 +1305031454.7595 1.2704 0.4218 1.5353 0.6649 0.5917 -0.2763 -0.3626 +1305031454.7695 1.2726 0.4211 1.5338 0.6667 0.5906 -0.2769 -0.3606 +1305031454.7795 1.2745 0.4205 1.5322 0.6681 0.5886 -0.2788 -0.3598 +1305031454.7896 1.2765 0.4198 1.5305 0.6693 0.5876 -0.2801 -0.3584 +1305031454.7995 1.2787 0.4191 1.5288 0.6709 0.5861 -0.2808 -0.3571 +1305031454.8095 1.2806 0.4182 1.5270 0.6721 0.5848 -0.2822 -0.3560 +1305031454.8195 1.2828 0.4174 1.5254 0.6741 0.5834 -0.2819 -0.3545 +1305031454.8295 1.2848 0.4165 1.5234 0.6764 0.5814 -0.2822 -0.3533 +1305031454.8395 1.2870 0.4155 1.5218 0.6788 0.5794 -0.2819 -0.3522 +1305031454.8495 1.2890 0.4145 1.5198 0.6812 0.5776 -0.2814 -0.3510 +1305031454.8595 1.2910 0.4134 1.5181 0.6835 0.5755 -0.2807 -0.3505 +1305031454.8694 1.2928 0.4121 1.5163 0.6858 0.5730 -0.2800 -0.3506 +1305031454.8795 1.2946 0.4107 1.5145 0.6880 0.5707 -0.2793 -0.3506 +1305031454.8895 1.2965 0.4091 1.5128 0.6902 0.5686 -0.2787 -0.3501 +1305031454.8995 1.2982 0.4076 1.5110 0.6922 0.5665 -0.2780 -0.3503 +1305031454.9095 1.3001 0.4059 1.5094 0.6948 0.5647 -0.2759 -0.3497 +1305031454.9197 1.3016 0.4041 1.5075 0.6965 0.5626 -0.2757 -0.3498 +1305031454.9295 1.3033 0.4022 1.5058 0.6985 0.5608 -0.2745 -0.3497 +1305031454.9394 1.3048 0.4000 1.5041 0.7005 0.5589 -0.2737 -0.3494 +1305031454.9494 1.3063 0.3978 1.5025 0.7021 0.5569 -0.2730 -0.3497 +1305031454.9606 1.3077 0.3955 1.5009 0.7041 0.5551 -0.2721 -0.3494 +1305031454.9695 1.3088 0.3929 1.4991 0.7054 0.5529 -0.2726 -0.3498 +1305031454.9795 1.3104 0.3902 1.4978 0.7075 0.5517 -0.2709 -0.3489 +1305031454.9894 1.3113 0.3876 1.4962 0.7077 0.5503 -0.2723 -0.3496 +1305031454.9995 1.3122 0.3847 1.4946 0.7083 0.5494 -0.2724 -0.3498 +1305031455.0098 1.3136 0.3816 1.4930 0.7093 0.5486 -0.2721 -0.3493 +1305031455.0195 1.3144 0.3785 1.4915 0.7102 0.5479 -0.2714 -0.3491 +1305031455.0295 1.3154 0.3752 1.4901 0.7117 0.5474 -0.2696 -0.3480 +1305031455.0395 1.3156 0.3720 1.4883 0.7118 0.5463 -0.2703 -0.3491 +1305031455.0495 1.3166 0.3684 1.4871 0.7137 0.5452 -0.2679 -0.3489 +1305031455.0595 1.3170 0.3649 1.4856 0.7141 0.5439 -0.2673 -0.3505 +1305031455.0695 1.3173 0.3613 1.4844 0.7144 0.5433 -0.2665 -0.3514 +1305031455.0795 1.3170 0.3576 1.4828 0.7131 0.5426 -0.2681 -0.3539 +1305031455.0895 1.3170 0.3539 1.4814 0.7129 0.5417 -0.2676 -0.3559 +1305031455.0995 1.3172 0.3500 1.4802 0.7134 0.5413 -0.2659 -0.3569 +1305031455.1096 1.3171 0.3461 1.4789 0.7140 0.5406 -0.2646 -0.3576 +1305031455.1195 1.3170 0.3422 1.4776 0.7152 0.5398 -0.2633 -0.3575 +1305031455.1295 1.3167 0.3383 1.4763 0.7164 0.5384 -0.2615 -0.3585 +1305031455.1395 1.3161 0.3345 1.4750 0.7173 0.5367 -0.2612 -0.3595 +1305031455.1495 1.3157 0.3304 1.4739 0.7191 0.5355 -0.2597 -0.3588 +1305031455.1596 1.3148 0.3264 1.4724 0.7198 0.5337 -0.2600 -0.3597 +1305031455.1695 1.3143 0.3224 1.4712 0.7221 0.5323 -0.2582 -0.3585 +1305031455.1794 1.3133 0.3185 1.4700 0.7238 0.5305 -0.2578 -0.3581 +1305031455.1895 1.3123 0.3145 1.4687 0.7255 0.5285 -0.2574 -0.3579 +1305031455.1995 1.3111 0.3105 1.4676 0.7270 0.5270 -0.2566 -0.3577 +1305031455.2095 1.3104 0.3065 1.4668 0.7286 0.5255 -0.2554 -0.3574 +1305031455.2197 1.3090 0.3025 1.4656 0.7290 0.5232 -0.2565 -0.3592 +1305031455.2295 1.3084 0.2987 1.4651 0.7309 0.5217 -0.2541 -0.3592 +1305031455.2395 1.3069 0.2948 1.4640 0.7324 0.5202 -0.2536 -0.3588 +1305031455.2495 1.3055 0.2910 1.4630 0.7343 0.5187 -0.2519 -0.3581 +1305031455.2595 1.3042 0.2873 1.4620 0.7368 0.5167 -0.2508 -0.3568 +1305031455.2694 1.3025 0.2837 1.4610 0.7391 0.5146 -0.2500 -0.3555 +1305031455.2795 1.3013 0.2795 1.4596 0.7427 0.5104 -0.2498 -0.3541 +1305031455.2894 1.2997 0.2758 1.4588 0.7451 0.5069 -0.2498 -0.3542 +1305031455.2995 1.2982 0.2719 1.4581 0.7476 0.5042 -0.2498 -0.3527 +1305031455.3094 1.2966 0.2679 1.4574 0.7500 0.5012 -0.2502 -0.3517 +1305031455.3194 1.2949 0.2640 1.4568 0.7520 0.4989 -0.2507 -0.3503 +1305031455.3294 1.2931 0.2601 1.4559 0.7539 0.4971 -0.2510 -0.3487 +1305031455.3394 1.2912 0.2562 1.4555 0.7566 0.4959 -0.2499 -0.3452 +1305031455.3495 1.2896 0.2525 1.4551 0.7591 0.4951 -0.2478 -0.3423 +1305031455.3596 1.2880 0.2484 1.4545 0.7623 0.4934 -0.2451 -0.3396 +1305031455.3694 1.2859 0.2446 1.4540 0.7652 0.4904 -0.2440 -0.3384 +1305031455.3795 1.2840 0.2409 1.4537 0.7681 0.4875 -0.2421 -0.3373 +1305031455.3895 1.2823 0.2369 1.4536 0.7717 0.4845 -0.2397 -0.3351 +1305031455.3995 1.2803 0.2329 1.4537 0.7748 0.4809 -0.2384 -0.3341 +1305031455.4095 1.2785 0.2289 1.4539 0.7771 0.4781 -0.2374 -0.3334 +1305031455.4194 1.2765 0.2247 1.4540 0.7798 0.4753 -0.2361 -0.3320 +1305031455.4294 1.2746 0.2206 1.4545 0.7822 0.4731 -0.2350 -0.3303 +1305031455.4395 1.2727 0.2163 1.4552 0.7845 0.4705 -0.2338 -0.3295 +1305031455.4494 1.2707 0.2122 1.4558 0.7858 0.4681 -0.2337 -0.3298 +1305031455.4595 1.2684 0.2079 1.4565 0.7878 0.4655 -0.2335 -0.3289 +1305031455.4694 1.2662 0.2035 1.4571 0.7898 0.4629 -0.2332 -0.3281 +1305031455.4795 1.2638 0.1992 1.4577 0.7923 0.4593 -0.2329 -0.3273 +1305031455.4902 1.2614 0.1948 1.4586 0.7947 0.4560 -0.2326 -0.3262 +1305031455.4995 1.2589 0.1902 1.4596 0.7976 0.4525 -0.2321 -0.3244 +1305031455.5095 1.2563 0.1857 1.4607 0.7994 0.4485 -0.2326 -0.3250 +1305031455.5194 1.2536 0.1810 1.4620 0.8014 0.4451 -0.2330 -0.3245 +1305031455.5295 1.2510 0.1762 1.4633 0.8032 0.4422 -0.2338 -0.3235 +1305031455.5395 1.2481 0.1714 1.4648 0.8046 0.4385 -0.2355 -0.3239 +1305031455.5495 1.2451 0.1666 1.4663 0.8061 0.4350 -0.2376 -0.3234 +1305031455.5594 1.2421 0.1614 1.4678 0.8080 0.4312 -0.2396 -0.3221 +1305031455.5694 1.2395 0.1563 1.4697 0.8107 0.4286 -0.2389 -0.3192 +1305031455.5795 1.2362 0.1513 1.4716 0.8125 0.4249 -0.2404 -0.3187 +1305031455.5894 1.2329 0.1462 1.4734 0.8151 0.4210 -0.2407 -0.3169 +1305031455.5995 1.2296 0.1412 1.4754 0.8178 0.4175 -0.2408 -0.3146 +1305031455.6095 1.2262 0.1363 1.4775 0.8197 0.4139 -0.2411 -0.3142 +1305031455.6195 1.2227 0.1311 1.4796 0.8214 0.4108 -0.2410 -0.3137 +1305031455.6294 1.2193 0.1262 1.4819 0.8226 0.4081 -0.2406 -0.3146 +1305031455.6394 1.2156 0.1213 1.4844 0.8227 0.4056 -0.2413 -0.3169 +1305031455.6494 1.2123 0.1162 1.4869 0.8229 0.4046 -0.2410 -0.3178 +1305031455.6594 1.2086 0.1112 1.4895 0.8227 0.4037 -0.2407 -0.3198 +1305031455.6694 1.2051 0.1062 1.4921 0.8224 0.4031 -0.2406 -0.3213 +1305031455.6794 1.2017 0.1011 1.4948 0.8226 0.4036 -0.2391 -0.3215 +1305031455.6895 1.1984 0.0962 1.4976 0.8223 0.4041 -0.2379 -0.3226 +1305031455.6995 1.1949 0.0913 1.5005 0.8220 0.4048 -0.2363 -0.3234 +1305031455.7096 1.1914 0.0866 1.5035 0.8217 0.4055 -0.2345 -0.3246 +1305031455.7194 1.1881 0.0818 1.5065 0.8217 0.4057 -0.2324 -0.3258 +1305031455.7295 1.1848 0.0773 1.5097 0.8216 0.4066 -0.2301 -0.3267 +1305031455.7394 1.1816 0.0728 1.5129 0.8217 0.4069 -0.2281 -0.3274 +1305031455.7494 1.1781 0.0684 1.5161 0.8221 0.4063 -0.2260 -0.3286 +1305031455.7594 1.1748 0.0641 1.5194 0.8227 0.4060 -0.2239 -0.3291 +1305031455.7695 1.1714 0.0602 1.5227 0.8219 0.4049 -0.2240 -0.3322 +1305031455.7795 1.1684 0.0559 1.5263 0.8224 0.4039 -0.2221 -0.3334 +1305031455.7895 1.1653 0.0517 1.5298 0.8227 0.4033 -0.2209 -0.3343 +1305031455.7994 1.1624 0.0477 1.5333 0.8225 0.4027 -0.2205 -0.3357 +1305031455.8094 1.1596 0.0435 1.5370 0.8228 0.4024 -0.2192 -0.3362 +1305031455.8194 1.1566 0.0396 1.5406 0.8224 0.4021 -0.2189 -0.3378 +1305031455.8295 1.1537 0.0354 1.5440 0.8229 0.4022 -0.2175 -0.3373 +1305031455.8394 1.1508 0.0316 1.5476 0.8228 0.4020 -0.2174 -0.3379 +1305031455.8495 1.1484 0.0276 1.5513 0.8236 0.4025 -0.2148 -0.3368 +1305031455.8595 1.1456 0.0240 1.5549 0.8231 0.4017 -0.2147 -0.3391 +1305031455.8694 1.1428 0.0204 1.5583 0.8237 0.4019 -0.2133 -0.3383 +1305031455.8794 1.1399 0.0166 1.5617 0.8240 0.4011 -0.2125 -0.3391 +1305031455.8894 1.1373 0.0133 1.5651 0.8244 0.4008 -0.2111 -0.3394 +1305031455.8995 1.1347 0.0097 1.5684 0.8253 0.4005 -0.2093 -0.3387 +1305031455.9098 1.1317 0.0064 1.5715 0.8252 0.4002 -0.2086 -0.3398 +1305031455.9194 1.1291 0.0030 1.5749 0.8256 0.4003 -0.2066 -0.3397 +1305031455.9294 1.1264 -0.0004 1.5780 0.8258 0.4003 -0.2053 -0.3401 +1305031455.9394 1.1237 -0.0038 1.5811 0.8259 0.4004 -0.2037 -0.3408 +1305031455.9495 1.1207 -0.0070 1.5840 0.8257 0.4004 -0.2026 -0.3418 +1305031455.9595 1.1181 -0.0102 1.5870 0.8264 0.4010 -0.1999 -0.3410 +1305031455.9694 1.1152 -0.0134 1.5897 0.8268 0.4007 -0.1985 -0.3411 +1305031455.9794 1.1125 -0.0164 1.5924 0.8273 0.4010 -0.1964 -0.3410 +1305031455.9895 1.1096 -0.0195 1.5951 0.8282 0.4009 -0.1933 -0.3406 +1305031455.9994 1.1067 -0.0225 1.5976 0.8286 0.4013 -0.1914 -0.3401 +1305031456.0094 1.1038 -0.0253 1.6000 0.8294 0.4018 -0.1882 -0.3394 +1305031456.0194 1.1009 -0.0283 1.6024 0.8305 0.4031 -0.1842 -0.3373 +1305031456.0295 1.0978 -0.0313 1.6046 0.8312 0.4046 -0.1807 -0.3357 +1305031456.0394 1.0949 -0.0340 1.6070 0.8318 0.4066 -0.1770 -0.3338 +1305031456.0495 1.0917 -0.0368 1.6091 0.8319 0.4083 -0.1743 -0.3328 +1305031456.0595 1.0888 -0.0394 1.6115 0.8324 0.4102 -0.1712 -0.3310 +1305031456.0695 1.0858 -0.0422 1.6136 0.8329 0.4112 -0.1686 -0.3298 +1305031456.0794 1.0826 -0.0447 1.6159 0.8331 0.4119 -0.1660 -0.3297 +1305031456.0904 1.0795 -0.0471 1.6179 0.8335 0.4116 -0.1646 -0.3297 +1305031456.0995 1.0763 -0.0495 1.6199 0.8337 0.4116 -0.1630 -0.3300 +1305031456.1095 1.0731 -0.0517 1.6221 0.8338 0.4115 -0.1615 -0.3306 +1305031456.1194 1.0699 -0.0540 1.6241 0.8342 0.4111 -0.1599 -0.3310 +1305031456.1295 1.0666 -0.0561 1.6261 0.8347 0.4104 -0.1583 -0.3312 +1305031456.1394 1.0635 -0.0582 1.6280 0.8356 0.4097 -0.1561 -0.3309 +1305031456.1495 1.0600 -0.0601 1.6297 0.8357 0.4089 -0.1547 -0.3324 +1305031456.1594 1.0570 -0.0619 1.6319 0.8362 0.4076 -0.1526 -0.3336 +1305031456.1694 1.0538 -0.0638 1.6338 0.8366 0.4062 -0.1506 -0.3352 +1305031456.1794 1.0505 -0.0654 1.6355 0.8365 0.4040 -0.1497 -0.3386 +1305031456.1894 1.0472 -0.0670 1.6373 0.8368 0.4021 -0.1475 -0.3410 +1305031456.1995 1.0437 -0.0683 1.6387 0.8371 0.3999 -0.1459 -0.3435 +1305031456.2094 1.0404 -0.0698 1.6401 0.8385 0.3980 -0.1431 -0.3435 +1305031456.2194 1.0369 -0.0713 1.6413 0.8397 0.3959 -0.1401 -0.3444 +1305031456.2294 1.0335 -0.0726 1.6424 0.8409 0.3940 -0.1369 -0.3448 +1305031456.2394 1.0297 -0.0738 1.6434 0.8419 0.3922 -0.1342 -0.3456 +1305031456.2494 1.0262 -0.0750 1.6444 0.8431 0.3904 -0.1306 -0.3460 +1305031456.2594 1.0226 -0.0760 1.6455 0.8438 0.3884 -0.1282 -0.3475 +1305031456.2694 1.0190 -0.0769 1.6464 0.8446 0.3858 -0.1256 -0.3493 +1305031456.2796 1.0154 -0.0779 1.6472 0.8451 0.3836 -0.1237 -0.3512 +1305031456.2894 1.0117 -0.0789 1.6480 0.8458 0.3807 -0.1222 -0.3532 +1305031456.2994 1.0080 -0.0799 1.6486 0.8469 0.3777 -0.1204 -0.3544 +1305031456.3095 1.0042 -0.0809 1.6492 0.8478 0.3745 -0.1185 -0.3564 +1305031456.3194 1.0004 -0.0817 1.6497 0.8486 0.3712 -0.1160 -0.3587 +1305031456.3294 0.9964 -0.0822 1.6499 0.8486 0.3679 -0.1151 -0.3623 +1305031456.3395 0.9925 -0.0829 1.6500 0.8494 0.3649 -0.1125 -0.3644 +1305031456.3498 0.9884 -0.0836 1.6500 0.8503 0.3622 -0.1096 -0.3657 +1305031456.3595 0.9846 -0.0843 1.6497 0.8517 0.3597 -0.1058 -0.3660 +1305031456.3694 0.9807 -0.0850 1.6495 0.8527 0.3577 -0.1027 -0.3666 +1305031456.3794 0.9767 -0.0856 1.6491 0.8534 0.3551 -0.1003 -0.3682 +1305031456.3894 0.9727 -0.0863 1.6488 0.8539 0.3526 -0.0973 -0.3701 +1305031456.3994 0.9685 -0.0868 1.6484 0.8538 0.3499 -0.0957 -0.3733 +1305031456.4095 0.9642 -0.0875 1.6478 0.8541 0.3470 -0.0941 -0.3759 +1305031456.4194 0.9599 -0.0882 1.6470 0.8546 0.3439 -0.0926 -0.3780 +1305031456.4295 0.9555 -0.0888 1.6459 0.8549 0.3415 -0.0916 -0.3797 +1305031456.4394 0.9512 -0.0895 1.6447 0.8560 0.3394 -0.0902 -0.3793 +1305031456.4494 0.9467 -0.0901 1.6431 0.8569 0.3377 -0.0895 -0.3790 +1305031456.4594 0.9422 -0.0909 1.6416 0.8586 0.3367 -0.0887 -0.3763 +1305031456.4694 0.9377 -0.0916 1.6398 0.8599 0.3355 -0.0885 -0.3743 +1305031456.4795 0.9330 -0.0922 1.6379 0.8612 0.3339 -0.0884 -0.3729 +1305031456.4894 0.9283 -0.0927 1.6359 0.8626 0.3330 -0.0887 -0.3704 +1305031456.4994 0.9235 -0.0933 1.6340 0.8636 0.3315 -0.0890 -0.3693 +1305031456.5095 0.9189 -0.0938 1.6319 0.8646 0.3303 -0.0896 -0.3680 +1305031456.5194 0.9142 -0.0943 1.6298 0.8659 0.3288 -0.0898 -0.3661 +1305031456.5294 0.9095 -0.0949 1.6278 0.8671 0.3274 -0.0898 -0.3645 +1305031456.5394 0.9048 -0.0955 1.6257 0.8677 0.3262 -0.0897 -0.3641 +1305031456.5494 0.9001 -0.0961 1.6237 0.8683 0.3240 -0.0897 -0.3648 +1305031456.5595 0.8953 -0.0965 1.6216 0.8685 0.3218 -0.0896 -0.3661 +1305031456.5694 0.8908 -0.0972 1.6195 0.8694 0.3195 -0.0888 -0.3662 +1305031456.5795 0.8860 -0.0976 1.6171 0.8702 0.3170 -0.0883 -0.3666 +1305031456.5894 0.8814 -0.0979 1.6146 0.8717 0.3147 -0.0866 -0.3654 +1305031456.5994 0.8768 -0.0984 1.6119 0.8741 0.3126 -0.0843 -0.3620 +1305031456.6095 0.8722 -0.0988 1.6092 0.8769 0.3107 -0.0817 -0.3575 +1305031456.6194 0.8677 -0.0990 1.6065 0.8798 0.3089 -0.0791 -0.3526 +1305031456.6294 0.8633 -0.0993 1.6037 0.8818 0.3070 -0.0767 -0.3496 +1305031456.6394 0.8589 -0.0998 1.6011 0.8838 0.3049 -0.0748 -0.3470 +1305031456.6494 0.8547 -0.1002 1.5987 0.8853 0.3024 -0.0733 -0.3455 +1305031456.6595 0.8502 -0.1005 1.5962 0.8858 0.2993 -0.0734 -0.3469 +1305031456.6694 0.8461 -0.1008 1.5939 0.8862 0.2965 -0.0738 -0.3482 +1305031456.6795 0.8418 -0.1012 1.5914 0.8866 0.2933 -0.0744 -0.3497 +1305031456.6895 0.8379 -0.1014 1.5890 0.8876 0.2906 -0.0746 -0.3496 +1305031456.6994 0.8335 -0.1021 1.5862 0.8890 0.2880 -0.0752 -0.3481 +1305031456.7094 0.8297 -0.1024 1.5833 0.8907 0.2852 -0.0751 -0.3459 +1305031456.7194 0.8255 -0.1030 1.5805 0.8925 0.2831 -0.0755 -0.3428 +1305031456.7294 0.8215 -0.1034 1.5778 0.8942 0.2817 -0.0757 -0.3397 +1305031456.7394 0.8174 -0.1038 1.5750 0.8948 0.2803 -0.0773 -0.3387 +1305031456.7494 0.8132 -0.1042 1.5724 0.8952 0.2794 -0.0793 -0.3380 +1305031456.7594 0.8089 -0.1047 1.5698 0.8951 0.2779 -0.0823 -0.3388 +1305031456.7694 0.8047 -0.1053 1.5673 0.8948 0.2767 -0.0856 -0.3397 +1305031456.7794 0.8008 -0.1056 1.5643 0.8944 0.2752 -0.0883 -0.3414 +1305031456.7895 0.7964 -0.1060 1.5618 0.8947 0.2736 -0.0907 -0.3411 +1305031456.7996 0.7922 -0.1065 1.5590 0.8955 0.2715 -0.0928 -0.3402 +1305031456.8096 0.7882 -0.1070 1.5561 0.8969 0.2692 -0.0935 -0.3382 +1305031456.8194 0.7841 -0.1074 1.5530 0.8984 0.2668 -0.0938 -0.3361 +1305031456.8294 0.7803 -0.1079 1.5500 0.8998 0.2647 -0.0938 -0.3338 +1305031456.8395 0.7762 -0.1084 1.5469 0.9011 0.2627 -0.0937 -0.3319 +1305031456.8494 0.7721 -0.1089 1.5440 0.9021 0.2607 -0.0928 -0.3311 +1305031456.8595 0.7681 -0.1095 1.5411 0.9028 0.2589 -0.0927 -0.3306 +1305031456.8694 0.7641 -0.1101 1.5382 0.9033 0.2575 -0.0920 -0.3305 +1305031456.8794 0.7602 -0.1108 1.5356 0.9040 0.2557 -0.0913 -0.3302 +1305031456.8894 0.7563 -0.1114 1.5331 0.9041 0.2537 -0.0905 -0.3316 +1305031456.8995 0.7524 -0.1121 1.5305 0.9040 0.2513 -0.0902 -0.3340 +1305031456.9095 0.7483 -0.1128 1.5279 0.9039 0.2481 -0.0893 -0.3367 +1305031456.9194 0.7447 -0.1136 1.5253 0.9045 0.2455 -0.0884 -0.3374 +1305031456.9294 0.7408 -0.1145 1.5227 0.9052 0.2427 -0.0871 -0.3380 +1305031456.9394 0.7369 -0.1155 1.5199 0.9063 0.2406 -0.0858 -0.3367 +1305031456.9495 0.7332 -0.1165 1.5174 0.9075 0.2388 -0.0835 -0.3352 +1305031456.9594 0.7292 -0.1177 1.5147 0.9087 0.2376 -0.0821 -0.3332 +1305031456.9694 0.7258 -0.1188 1.5124 0.9099 0.2373 -0.0801 -0.3308 +1305031456.9794 0.7217 -0.1202 1.5101 0.9107 0.2363 -0.0788 -0.3294 +1305031456.9894 0.7180 -0.1218 1.5081 0.9117 0.2363 -0.0773 -0.3270 +1305031456.9994 0.7144 -0.1229 1.5062 0.9117 0.2347 -0.0762 -0.3285 +1305031457.0095 0.7107 -0.1243 1.5046 0.9119 0.2327 -0.0752 -0.3296 +1305031457.0195 0.7071 -0.1257 1.5030 0.9124 0.2306 -0.0742 -0.3298 +1305031457.0295 0.7034 -0.1272 1.5015 0.9131 0.2277 -0.0733 -0.3300 +1305031457.0395 0.7001 -0.1288 1.5001 0.9144 0.2259 -0.0716 -0.3281 +1305031457.0494 0.6966 -0.1305 1.4988 0.9158 0.2236 -0.0702 -0.3261 +1305031457.0594 0.6929 -0.1322 1.4976 0.9171 0.2217 -0.0684 -0.3243 +1305031457.0694 0.6896 -0.1341 1.4967 0.9186 0.2201 -0.0663 -0.3215 +1305031457.0794 0.6863 -0.1360 1.4959 0.9197 0.2186 -0.0643 -0.3198 +1305031457.0894 0.6828 -0.1380 1.4956 0.9207 0.2168 -0.0627 -0.3185 +1305031457.0994 0.6795 -0.1398 1.4953 0.9211 0.2154 -0.0614 -0.3185 +1305031457.1094 0.6761 -0.1420 1.4953 0.9216 0.2133 -0.0595 -0.3187 +1305031457.1194 0.6730 -0.1441 1.4957 0.9220 0.2111 -0.0582 -0.3193 +1305031457.1295 0.6696 -0.1462 1.4960 0.9223 0.2081 -0.0567 -0.3208 +1305031457.1394 0.6663 -0.1485 1.4964 0.9227 0.2053 -0.0555 -0.3214 +1305031457.1494 0.6629 -0.1507 1.4970 0.9233 0.2023 -0.0544 -0.3219 +1305031457.1594 0.6596 -0.1531 1.4978 0.9238 0.1996 -0.0529 -0.3223 +1305031457.1694 0.6562 -0.1558 1.4987 0.9240 0.1967 -0.0521 -0.3238 +1305031457.1794 0.6527 -0.1581 1.4995 0.9243 0.1944 -0.0509 -0.3244 +1305031457.1894 0.6496 -0.1607 1.5004 0.9252 0.1917 -0.0489 -0.3239 +1305031457.1995 0.6460 -0.1634 1.5013 0.9259 0.1896 -0.0473 -0.3234 +1305031457.2098 0.6425 -0.1662 1.5023 0.9267 0.1870 -0.0454 -0.3228 +1305031457.2194 0.6390 -0.1691 1.5036 0.9275 0.1849 -0.0436 -0.3218 +1305031457.2295 0.6356 -0.1720 1.5050 0.9279 0.1823 -0.0422 -0.3224 +1305031457.2394 0.6319 -0.1750 1.5065 0.9277 0.1801 -0.0414 -0.3244 +1305031457.2494 0.6283 -0.1780 1.5082 0.9272 0.1775 -0.0401 -0.3274 +1305031457.2594 0.6246 -0.1812 1.5099 0.9270 0.1744 -0.0391 -0.3298 +1305031457.2694 0.6211 -0.1843 1.5118 0.9267 0.1713 -0.0381 -0.3324 +1305031457.2794 0.6173 -0.1877 1.5135 0.9267 0.1677 -0.0365 -0.3344 +1305031457.2895 0.6137 -0.1906 1.5154 0.9261 0.1648 -0.0350 -0.3375 +1305031457.2994 0.6099 -0.1940 1.5174 0.9266 0.1617 -0.0325 -0.3379 +1305031457.3094 0.6063 -0.1974 1.5192 0.9269 0.1595 -0.0302 -0.3383 +1305031457.3194 0.6026 -0.2007 1.5211 0.9274 0.1566 -0.0272 -0.3387 +1305031457.3294 0.5989 -0.2040 1.5231 0.9278 0.1541 -0.0246 -0.3390 +1305031457.3394 0.5953 -0.2073 1.5252 0.9280 0.1513 -0.0221 -0.3397 +1305031457.3494 0.5916 -0.2105 1.5275 0.9285 0.1483 -0.0190 -0.3398 +1305031457.3594 0.5881 -0.2138 1.5299 0.9286 0.1449 -0.0169 -0.3412 +1305031457.3694 0.5843 -0.2170 1.5325 0.9282 0.1419 -0.0144 -0.3438 +1305031457.3794 0.5806 -0.2200 1.5350 0.9275 0.1379 -0.0130 -0.3471 +1305031457.3894 0.5769 -0.2231 1.5378 0.9273 0.1344 -0.0115 -0.3490 +1305031457.3994 0.5731 -0.2264 1.5405 0.9278 0.1310 -0.0101 -0.3490 +1305031457.4094 0.5694 -0.2295 1.5433 0.9281 0.1281 -0.0086 -0.3496 +1305031457.4194 0.5657 -0.2326 1.5461 0.9282 0.1258 -0.0075 -0.3500 +1305031457.4294 0.5618 -0.2357 1.5491 0.9285 0.1239 -0.0072 -0.3500 +1305031457.4394 0.5579 -0.2387 1.5520 0.9287 0.1221 -0.0066 -0.3502 +1305031457.4495 0.5543 -0.2418 1.5551 0.9292 0.1208 -0.0060 -0.3492 +1305031457.4594 0.5501 -0.2447 1.5581 0.9290 0.1193 -0.0062 -0.3502 +1305031457.4694 0.5462 -0.2477 1.5611 0.9292 0.1178 -0.0059 -0.3502 +1305031457.4794 0.5424 -0.2506 1.5644 0.9290 0.1164 -0.0055 -0.3513 +1305031457.4894 0.5384 -0.2536 1.5674 0.9290 0.1149 -0.0052 -0.3518 +1305031457.4994 0.5345 -0.2564 1.5706 0.9287 0.1132 -0.0047 -0.3532 +1305031457.5094 0.5306 -0.2595 1.5738 0.9285 0.1119 -0.0039 -0.3539 +1305031457.5194 0.5267 -0.2624 1.5769 0.9281 0.1104 -0.0035 -0.3556 +1305031457.5294 0.5229 -0.2653 1.5800 0.9278 0.1088 -0.0025 -0.3570 +1305031457.5394 0.5191 -0.2683 1.5829 0.9277 0.1068 -0.0015 -0.3578 +1305031457.5494 0.5151 -0.2710 1.5858 0.9272 0.1049 -0.0009 -0.3596 +1305031457.5595 0.5115 -0.2739 1.5888 0.9271 0.1031 0.0006 -0.3603 +1305031457.5694 0.5076 -0.2767 1.5916 0.9270 0.1014 0.0011 -0.3612 +1305031457.5794 0.5037 -0.2796 1.5943 0.9271 0.1001 0.0021 -0.3613 +1305031457.5894 0.4999 -0.2818 1.5969 0.9270 0.0986 0.0026 -0.3619 +1305031457.5994 0.4958 -0.2846 1.5996 0.9275 0.0975 0.0028 -0.3609 +1305031457.6094 0.4919 -0.2869 1.6024 0.9276 0.0968 0.0033 -0.3608 +1305031457.6194 0.4877 -0.2892 1.6048 0.9272 0.0950 0.0035 -0.3623 +1305031457.6294 0.4838 -0.2912 1.6076 0.9269 0.0938 0.0039 -0.3634 +1305031457.6394 0.4798 -0.2934 1.6105 0.9269 0.0926 0.0041 -0.3638 +1305031457.6494 0.4757 -0.2956 1.6129 0.9270 0.0908 0.0046 -0.3639 +1305031457.6594 0.4716 -0.2976 1.6153 0.9276 0.0896 0.0042 -0.3627 +1305031457.6694 0.4674 -0.2995 1.6178 0.9283 0.0884 0.0047 -0.3611 +1305031457.6794 0.4631 -0.3016 1.6201 0.9290 0.0877 0.0052 -0.3594 +1305031457.6896 0.4588 -0.3038 1.6227 0.9299 0.0876 0.0060 -0.3571 +1305031457.6994 0.4545 -0.3056 1.6252 0.9300 0.0876 0.0065 -0.3569 +1305031457.7095 0.4500 -0.3075 1.6279 0.9297 0.0875 0.0070 -0.3577 +1305031457.7194 0.4456 -0.3094 1.6307 0.9295 0.0878 0.0079 -0.3583 +1305031457.7294 0.4412 -0.3111 1.6332 0.9288 0.0876 0.0089 -0.3600 +1305031457.7394 0.4369 -0.3130 1.6360 0.9284 0.0877 0.0098 -0.3610 +1305031457.7494 0.4325 -0.3147 1.6386 0.9280 0.0877 0.0107 -0.3621 +1305031457.7595 0.4280 -0.3166 1.6415 0.9277 0.0873 0.0113 -0.3627 +1305031457.7694 0.4237 -0.3182 1.6444 0.9267 0.0868 0.0125 -0.3655 +1305031457.7794 0.4194 -0.3197 1.6473 0.9253 0.0861 0.0138 -0.3690 +1305031457.7894 0.4149 -0.3214 1.6503 0.9243 0.0850 0.0148 -0.3718 +1305031457.7994 0.4106 -0.3229 1.6532 0.9231 0.0836 0.0163 -0.3750 +1305031457.8094 0.4064 -0.3245 1.6559 0.9222 0.0825 0.0180 -0.3773 +1305031457.8194 0.4019 -0.3256 1.6585 0.9213 0.0810 0.0201 -0.3797 +1305031457.8294 0.3976 -0.3266 1.6609 0.9205 0.0787 0.0229 -0.3821 +1305031457.8394 0.3933 -0.3280 1.6635 0.9207 0.0779 0.0252 -0.3817 +1305031457.8494 0.3888 -0.3293 1.6661 0.9207 0.0771 0.0271 -0.3816 +1305031457.8594 0.3845 -0.3300 1.6685 0.9195 0.0751 0.0297 -0.3846 +1305031457.8694 0.3799 -0.3310 1.6710 0.9186 0.0744 0.0317 -0.3868 +1305031457.8794 0.3754 -0.3320 1.6736 0.9172 0.0732 0.0327 -0.3903 +1305031457.8894 0.3710 -0.3329 1.6763 0.9156 0.0724 0.0337 -0.3940 +1305031457.8994 0.3665 -0.3337 1.6788 0.9142 0.0713 0.0342 -0.3975 +1305031457.9094 0.3620 -0.3347 1.6812 0.9132 0.0698 0.0343 -0.4001 +1305031457.9195 0.3574 -0.3351 1.6834 0.9117 0.0680 0.0341 -0.4038 +1305031457.9295 0.3527 -0.3360 1.6854 0.9116 0.0661 0.0337 -0.4044 +1305031457.9394 0.3480 -0.3365 1.6872 0.9113 0.0645 0.0333 -0.4053 +1305031457.9494 0.3433 -0.3368 1.6888 0.9108 0.0631 0.0330 -0.4066 +1305031457.9594 0.3384 -0.3373 1.6903 0.9107 0.0623 0.0328 -0.4071 +1305031457.9694 0.3336 -0.3377 1.6917 0.9102 0.0615 0.0328 -0.4082 +1305031457.9796 0.3289 -0.3379 1.6931 0.9098 0.0610 0.0331 -0.4091 +1305031457.9894 0.3237 -0.3379 1.6942 0.9083 0.0603 0.0331 -0.4125 +1305031457.9994 0.3188 -0.3380 1.6954 0.9076 0.0597 0.0338 -0.4143 +1305031458.0098 0.3137 -0.3379 1.6964 0.9062 0.0587 0.0343 -0.4173 +1305031458.0194 0.3087 -0.3378 1.6973 0.9051 0.0576 0.0353 -0.4197 +1305031458.0294 0.3035 -0.3374 1.6980 0.9036 0.0561 0.0361 -0.4232 +1305031458.0395 0.2983 -0.3370 1.6982 0.9031 0.0544 0.0371 -0.4244 +1305031458.0494 0.2930 -0.3366 1.6984 0.9020 0.0526 0.0384 -0.4267 +1305031458.0594 0.2875 -0.3358 1.6983 0.9017 0.0510 0.0391 -0.4276 +1305031458.0694 0.2823 -0.3351 1.6981 0.9020 0.0497 0.0406 -0.4269 +1305031458.0794 0.2768 -0.3342 1.6977 0.9023 0.0487 0.0419 -0.4264 +1305031458.0894 0.2713 -0.3333 1.6971 0.9030 0.0474 0.0435 -0.4249 +1305031458.0995 0.2656 -0.3322 1.6964 0.9030 0.0467 0.0450 -0.4248 +1305031458.1095 0.2600 -0.3310 1.6957 0.9031 0.0461 0.0465 -0.4245 +1305031458.1194 0.2542 -0.3296 1.6950 0.9026 0.0457 0.0476 -0.4255 +1305031458.1294 0.2485 -0.3284 1.6943 0.9029 0.0454 0.0489 -0.4245 +1305031458.1394 0.2425 -0.3269 1.6933 0.9026 0.0448 0.0497 -0.4253 +1305031458.1497 0.2367 -0.3254 1.6925 0.9018 0.0434 0.0504 -0.4270 +1305031458.1594 0.2306 -0.3236 1.6913 0.9018 0.0418 0.0504 -0.4273 +1305031458.1694 0.2246 -0.3218 1.6901 0.9019 0.0407 0.0503 -0.4271 +1305031458.1794 0.2184 -0.3200 1.6887 0.9023 0.0395 0.0500 -0.4264 +1305031458.1894 0.2122 -0.3181 1.6873 0.9031 0.0387 0.0495 -0.4247 +1305031458.1994 0.2060 -0.3161 1.6858 0.9044 0.0380 0.0500 -0.4220 +1305031458.2094 0.1997 -0.3141 1.6842 0.9058 0.0383 0.0499 -0.4191 +1305031458.2194 0.1934 -0.3120 1.6825 0.9067 0.0388 0.0502 -0.4169 +1305031458.2294 0.1870 -0.3100 1.6811 0.9077 0.0395 0.0500 -0.4148 +1305031458.2394 0.1806 -0.3078 1.6797 0.9078 0.0403 0.0504 -0.4143 +1305031458.2496 0.1742 -0.3057 1.6785 0.9071 0.0412 0.0503 -0.4158 +1305031458.2594 0.1676 -0.3034 1.6773 0.9061 0.0418 0.0495 -0.4182 +1305031458.2694 0.1611 -0.3013 1.6760 0.9048 0.0423 0.0484 -0.4209 +1305031458.2794 0.1546 -0.2988 1.6746 0.9034 0.0422 0.0471 -0.4241 +1305031458.2894 0.1483 -0.2966 1.6730 0.9038 0.0425 0.0457 -0.4234 +1305031458.2994 0.1420 -0.2944 1.6712 0.9038 0.0422 0.0443 -0.4235 +1305031458.3096 0.1358 -0.2920 1.6694 0.9037 0.0418 0.0428 -0.4239 +1305031458.3194 0.1295 -0.2897 1.6675 0.9040 0.0414 0.0414 -0.4235 +1305031458.3294 0.1235 -0.2876 1.6656 0.9040 0.0414 0.0403 -0.4236 +1305031458.3394 0.1175 -0.2853 1.6636 0.9028 0.0414 0.0387 -0.4262 +1305031458.3494 0.1116 -0.2829 1.6616 0.9016 0.0411 0.0374 -0.4291 +1305031458.3602 0.1059 -0.2803 1.6594 0.8996 0.0409 0.0365 -0.4332 +1305031458.3694 0.1003 -0.2780 1.6570 0.8981 0.0401 0.0350 -0.4365 +1305031458.3794 0.0949 -0.2756 1.6545 0.8972 0.0388 0.0337 -0.4385 +1305031458.3894 0.0897 -0.2731 1.6517 0.8962 0.0371 0.0325 -0.4408 +1305031458.3994 0.0848 -0.2704 1.6488 0.8955 0.0350 0.0317 -0.4426 +1305031458.4094 0.0800 -0.2681 1.6455 0.8951 0.0314 0.0302 -0.4437 +1305031458.4194 0.0753 -0.2655 1.6420 0.8940 0.0278 0.0291 -0.4463 +1305031458.4294 0.0709 -0.2631 1.6385 0.8930 0.0243 0.0288 -0.4486 +1305031458.4394 0.0667 -0.2605 1.6348 0.8913 0.0210 0.0289 -0.4521 +1305031458.4494 0.0625 -0.2580 1.6312 0.8890 0.0181 0.0296 -0.4565 +1305031458.4594 0.0583 -0.2555 1.6274 0.8867 0.0160 0.0310 -0.4611 +1305031458.4694 0.0546 -0.2530 1.6234 0.8830 0.0144 0.0331 -0.4680 +1305031458.4794 0.0510 -0.2506 1.6192 0.8788 0.0132 0.0353 -0.4757 +1305031458.4894 0.0474 -0.2484 1.6148 0.8751 0.0124 0.0377 -0.4823 +1305031458.4994 0.0440 -0.2459 1.6103 0.8714 0.0111 0.0396 -0.4889 +1305031458.5094 0.0407 -0.2434 1.6055 0.8685 0.0105 0.0414 -0.4938 +1305031458.5194 0.0377 -0.2414 1.6001 0.8671 0.0086 0.0432 -0.4961 +1305031458.5294 0.0347 -0.2389 1.5946 0.8652 0.0071 0.0453 -0.4992 +1305031458.5394 0.0320 -0.2366 1.5892 -0.8637 -0.0063 -0.0476 0.5016 +1305031458.5494 0.0294 -0.2339 1.5838 -0.8625 -0.0057 -0.0502 0.5036 +1305031458.5594 0.0267 -0.2312 1.5784 -0.8607 -0.0057 -0.0527 0.5064 +1305031458.5694 0.0240 -0.2283 1.5729 -0.8587 -0.0066 -0.0547 0.5096 +1305031458.5794 0.0218 -0.2256 1.5674 -0.8575 -0.0075 -0.0561 0.5113 +1305031458.5894 0.0196 -0.2225 1.5619 -0.8546 -0.0090 -0.0572 0.5160 +1305031458.5994 0.0174 -0.2194 1.5561 -0.8534 -0.0106 -0.0576 0.5180 +1305031458.6094 0.0154 -0.2163 1.5502 -0.8532 -0.0119 -0.0578 0.5182 +1305031458.6194 0.0135 -0.2130 1.5443 -0.8533 -0.0127 -0.0580 0.5180 +1305031458.6294 0.0118 -0.2102 1.5383 -0.8550 -0.0129 -0.0583 0.5152 +1305031458.6394 0.0099 -0.2072 1.5323 -0.8564 -0.0130 -0.0577 0.5130 +1305031458.6494 0.0082 -0.2041 1.5265 -0.8570 -0.0145 -0.0564 0.5120 +1305031458.6607 0.0066 -0.2011 1.5206 -0.8578 -0.0169 -0.0539 0.5108 +1305031458.6694 0.0048 -0.1980 1.5149 -0.8590 -0.0202 -0.0502 0.5091 +1305031458.6794 0.0035 -0.1949 1.5091 -0.8605 -0.0251 -0.0469 0.5067 +1305031458.6894 0.0022 -0.1920 1.5035 -0.8617 -0.0296 -0.0431 0.5048 +1305031458.6994 0.0010 -0.1891 1.4980 -0.8623 -0.0341 -0.0404 0.5036 +1305031458.7094 -0.0001 -0.1861 1.4928 -0.8626 -0.0381 -0.0374 0.5030 +1305031458.7194 -0.0011 -0.1831 1.4878 -0.8616 -0.0422 -0.0348 0.5046 +1305031458.7294 -0.0020 -0.1802 1.4831 -0.8610 -0.0464 -0.0318 0.5055 +1305031458.7394 -0.0028 -0.1770 1.4785 -0.8591 -0.0509 -0.0292 0.5084 +1305031458.7494 -0.0036 -0.1742 1.4741 -0.8580 -0.0568 -0.0256 0.5099 +1305031458.7596 -0.0043 -0.1717 1.4698 -0.8582 -0.0625 -0.0218 0.5091 +1305031458.7694 -0.0051 -0.1692 1.4658 -0.8586 -0.0683 -0.0173 0.5078 +1305031458.7794 -0.0059 -0.1665 1.4618 -0.8591 -0.0721 -0.0146 0.5064 +1305031458.7895 -0.0068 -0.1636 1.4578 -0.8593 -0.0756 -0.0124 0.5057 +1305031458.7994 -0.0077 -0.1609 1.4541 -0.8603 -0.0780 -0.0102 0.5037 +1305031458.8094 -0.0087 -0.1581 1.4507 -0.8612 -0.0798 -0.0090 0.5019 +1305031458.8193 -0.0096 -0.1554 1.4475 -0.8620 -0.0804 -0.0073 0.5004 +1305031458.8294 -0.0107 -0.1529 1.4446 0.8624 0.0805 0.0060 -0.4998 +1305031458.8394 -0.0123 -0.1508 1.4419 0.8625 0.0813 0.0047 -0.4995 +1305031458.8494 -0.0138 -0.1484 1.4397 -0.8615 -0.0825 -0.0043 0.5011 +1305031458.8594 -0.0156 -0.1466 1.4376 -0.8599 -0.0847 -0.0041 0.5034 +1305031458.8694 -0.0174 -0.1446 1.4358 -0.8582 -0.0869 -0.0055 0.5059 +1305031458.8794 -0.0198 -0.1425 1.4340 -0.8564 -0.0886 -0.0069 0.5086 +1305031458.8894 -0.0221 -0.1409 1.4323 -0.8560 -0.0886 -0.0090 0.5092 +1305031458.8994 -0.0246 -0.1392 1.4309 -0.8561 -0.0877 -0.0108 0.5092 +1305031458.9094 -0.0271 -0.1372 1.4296 -0.8567 -0.0846 -0.0123 0.5087 +1305031458.9194 -0.0299 -0.1355 1.4284 -0.8582 -0.0804 -0.0132 0.5068 +1305031458.9294 -0.0329 -0.1334 1.4271 -0.8593 -0.0757 -0.0136 0.5057 +1305031458.9394 -0.0363 -0.1316 1.4261 -0.8612 -0.0711 -0.0140 0.5031 +1305031458.9494 -0.0399 -0.1299 1.4254 -0.8629 -0.0666 -0.0152 0.5008 +1305031458.9594 -0.0438 -0.1282 1.4245 0.8643 0.0634 0.0165 -0.4987 +1305031458.9694 -0.0480 -0.1264 1.4241 0.8643 0.0618 0.0181 -0.4988 +1305031458.9793 -0.0526 -0.1247 1.4239 -0.8631 -0.0612 -0.0192 0.5009 +1305031458.9894 -0.0575 -0.1230 1.4239 -0.8620 -0.0618 -0.0195 0.5027 +1305031458.9994 -0.0625 -0.1211 1.4239 -0.8601 -0.0622 -0.0193 0.5060 +1305031459.0094 -0.0678 -0.1192 1.4238 -0.8584 -0.0628 -0.0183 0.5088 +1305031459.0194 -0.0733 -0.1175 1.4237 -0.8576 -0.0626 -0.0167 0.5102 +1305031459.0295 -0.0789 -0.1158 1.4236 -0.8571 -0.0615 -0.0144 0.5113 +1305031459.0394 -0.0846 -0.1140 1.4234 -0.8565 -0.0595 -0.0113 0.5125 +1305031459.0494 -0.0903 -0.1120 1.4232 -0.8552 -0.0574 -0.0075 0.5150 +1305031459.0594 -0.0964 -0.1104 1.4230 -0.8548 -0.0551 -0.0026 0.5161 +1305031459.0694 -0.1027 -0.1085 1.4226 -0.8536 -0.0534 0.0027 0.5181 +1305031459.0793 -0.1090 -0.1068 1.4224 -0.8525 -0.0529 0.0088 0.5199 +1305031459.0894 -0.1157 -0.1048 1.4219 -0.8507 -0.0529 0.0149 0.5228 +1305031459.0994 -0.1226 -0.1031 1.4216 -0.8491 -0.0536 0.0218 0.5251 +1305031459.1094 -0.1292 -0.1014 1.4212 -0.8485 -0.0562 0.0292 0.5254 +1305031459.1194 -0.1359 -0.1001 1.4206 -0.8479 -0.0581 0.0365 0.5256 +1305031459.1294 -0.1428 -0.0982 1.4197 -0.8461 -0.0604 0.0434 0.5278 +1305031459.1394 -0.1494 -0.0967 1.4187 -0.8454 -0.0629 0.0502 0.5280 +1305031459.1494 -0.1559 -0.0951 1.4176 -0.8444 -0.0640 0.0568 0.5289 +1305031459.1594 -0.1624 -0.0936 1.4164 -0.8435 -0.0655 0.0625 0.5294 +1305031459.1694 -0.1686 -0.0920 1.4150 -0.8428 -0.0659 0.0680 0.5299 +1305031459.1793 -0.1747 -0.0903 1.4134 -0.8424 -0.0655 0.0735 0.5299 +1305031459.1894 -0.1805 -0.0888 1.4117 -0.8427 -0.0646 0.0782 0.5287 +1305031459.1994 -0.1864 -0.0873 1.4098 -0.8424 -0.0630 0.0823 0.5288 +1305031459.2094 -0.1920 -0.0857 1.4079 -0.8421 -0.0605 0.0867 0.5289 +1305031459.2194 -0.1974 -0.0842 1.4056 -0.8422 -0.0584 0.0900 0.5284 +1305031459.2294 -0.2026 -0.0832 1.4034 -0.8430 -0.0563 0.0935 0.5267 +1305031459.2394 -0.2076 -0.0821 1.4010 -0.8433 -0.0534 0.0954 0.5262 +1305031459.2494 -0.2124 -0.0810 1.3985 -0.8437 -0.0500 0.0961 0.5257 +1305031459.2594 -0.2171 -0.0799 1.3959 -0.8445 -0.0451 0.0954 0.5251 +1305031459.2694 -0.2215 -0.0792 1.3932 -0.8453 -0.0399 0.0936 0.5245 +1305031459.2794 -0.2258 -0.0783 1.3906 -0.8457 -0.0337 0.0909 0.5248 +1305031459.2894 -0.2299 -0.0779 1.3878 -0.8468 -0.0272 0.0879 0.5238 +1305031459.2994 -0.2335 -0.0772 1.3849 -0.8469 -0.0203 0.0841 0.5247 +1305031459.3094 -0.2373 -0.0771 1.3820 -0.8477 -0.0135 0.0806 0.5241 +1305031459.3194 -0.2410 -0.0770 1.3791 -0.8476 -0.0052 0.0765 0.5251 +1305031459.3294 -0.2443 -0.0772 1.3763 -0.8473 0.0030 0.0720 0.5261 +1305031459.3394 -0.2477 -0.0772 1.3733 -0.8459 0.0114 0.0682 0.5289 +1305031459.3494 -0.2510 -0.0774 1.3704 -0.8452 0.0204 0.0642 0.5302 +1305031459.3594 -0.2543 -0.0778 1.3674 -0.8443 0.0308 0.0604 0.5316 +1305031459.3694 -0.2570 -0.0781 1.3636 -0.8420 0.0410 0.0562 0.5350 +1305031459.3794 -0.2603 -0.0791 1.3599 -0.8446 0.0519 0.0524 0.5303 +1305031459.3894 -0.2633 -0.0801 1.3564 -0.8470 0.0647 0.0481 0.5254 +1305031459.3994 -0.2661 -0.0809 1.3527 -0.8489 0.0788 0.0429 0.5209 +1305031459.4094 -0.2688 -0.0820 1.3490 -0.8509 0.0937 0.0369 0.5156 +1305031459.4194 -0.2714 -0.0830 1.3454 -0.8489 0.1096 0.0306 0.5161 +1305031459.4294 -0.2743 -0.0839 1.3419 -0.8481 0.1256 0.0237 0.5142 +1305031459.4393 -0.2772 -0.0852 1.3385 -0.8452 0.1407 0.0181 0.5153 +1305031459.4494 -0.2799 -0.0868 1.3350 -0.8409 0.1556 0.0122 0.5182 +1305031459.4594 -0.2833 -0.0884 1.3314 -0.8399 0.1682 0.0093 0.5160 +1305031459.4697 -0.2865 -0.0897 1.3278 -0.8378 0.1806 0.0063 0.5152 +1305031459.4794 -0.2900 -0.0914 1.3243 -0.8374 0.1927 0.0050 0.5115 +1305031459.4895 -0.2934 -0.0930 1.3206 -0.8368 0.2044 0.0033 0.5080 +1305031459.4994 -0.2969 -0.0946 1.3172 -0.8371 0.2165 0.0013 0.5024 +1305031459.5095 -0.3004 -0.0960 1.3138 0.8365 -0.2282 0.0012 -0.4982 +1305031459.5194 -0.3040 -0.0973 1.3106 0.8355 -0.2388 0.0046 -0.4949 +1305031459.5294 -0.3076 -0.0986 1.3077 0.8341 -0.2485 0.0069 -0.4924 +1305031459.5394 -0.3117 -0.0997 1.3049 0.8323 -0.2569 0.0093 -0.4912 +1305031459.5494 -0.3157 -0.1008 1.3021 0.8305 -0.2638 0.0108 -0.4904 +1305031459.5593 -0.3200 -0.1018 1.2994 0.8288 -0.2704 0.0118 -0.4898 +1305031459.5693 -0.3248 -0.1029 1.2969 0.8280 -0.2762 0.0113 -0.4878 +1305031459.5794 -0.3294 -0.1034 1.2946 0.8260 -0.2822 0.0116 -0.4879 +1305031459.5894 -0.3344 -0.1037 1.2925 0.8251 -0.2868 0.0115 -0.4866 +1305031459.5995 -0.3395 -0.1041 1.2906 0.8252 -0.2904 0.0107 -0.4843 +1305031459.6094 -0.3446 -0.1039 1.2888 0.8245 -0.2932 0.0110 -0.4838 +1305031459.6194 -0.3499 -0.1039 1.2874 0.8244 -0.2948 0.0119 -0.4831 +1305031459.6294 -0.3551 -0.1035 1.2861 0.8239 -0.2958 0.0133 -0.4833 +1305031459.6393 -0.3605 -0.1032 1.2852 0.8233 -0.2973 0.0159 -0.4833 +1305031459.6494 -0.3657 -0.1027 1.2843 0.8218 -0.2996 0.0191 -0.4842 +1305031459.6594 -0.3711 -0.1021 1.2837 0.8210 -0.3023 0.0223 -0.4838 +1305031459.6694 -0.3767 -0.1017 1.2834 0.8215 -0.3055 0.0253 -0.4808 +1305031459.6794 -0.3822 -0.1010 1.2832 0.8214 -0.3087 0.0283 -0.4787 +1305031459.6894 -0.3879 -0.1003 1.2834 0.8215 -0.3120 0.0311 -0.4764 +1305031459.6994 -0.3933 -0.0991 1.2840 0.8216 -0.3140 0.0340 -0.4745 +1305031459.7094 -0.3990 -0.0981 1.2846 0.8220 -0.3154 0.0365 -0.4728 +1305031459.7194 -0.4047 -0.0969 1.2856 0.8222 -0.3156 0.0391 -0.4721 +1305031459.7294 -0.4105 -0.0957 1.2867 0.8220 -0.3154 0.0418 -0.4723 +1305031459.7393 -0.4159 -0.0941 1.2881 0.8208 -0.3153 0.0451 -0.4741 +1305031459.7494 -0.4216 -0.0926 1.2897 0.8207 -0.3151 0.0471 -0.4742 +1305031459.7594 -0.4272 -0.0908 1.2912 0.8201 -0.3143 0.0493 -0.4756 +1305031459.7694 -0.4329 -0.0891 1.2929 0.8205 -0.3143 0.0507 -0.4748 +1305031459.7794 -0.4384 -0.0872 1.2944 0.8202 -0.3142 0.0519 -0.4752 +1305031459.7894 -0.4439 -0.0852 1.2961 0.8206 -0.3135 0.0524 -0.4749 +1305031459.7994 -0.4496 -0.0831 1.2976 0.8207 -0.3134 0.0529 -0.4749 +1305031459.8094 -0.4549 -0.0811 1.2993 0.8215 -0.3130 0.0536 -0.4736 +1305031459.8194 -0.4605 -0.0785 1.3008 0.8220 -0.3124 0.0531 -0.4731 +1305031459.8294 -0.4656 -0.0757 1.3022 0.8220 -0.3124 0.0542 -0.4730 +1305031459.8394 -0.4709 -0.0732 1.3035 0.8231 -0.3120 0.0542 -0.4714 +1305031459.8494 -0.4761 -0.0703 1.3050 0.8238 -0.3119 0.0540 -0.4703 +1305031459.8594 -0.4816 -0.0673 1.3061 0.8240 -0.3121 0.0538 -0.4698 +1305031459.8693 -0.4866 -0.0646 1.3073 0.8246 -0.3127 0.0529 -0.4684 +1305031459.8794 -0.4914 -0.0620 1.3090 0.8269 -0.3120 0.0512 -0.4651 +1305031459.8894 -0.4962 -0.0590 1.3105 0.8273 -0.3119 0.0504 -0.4645 +1305031459.8994 -0.5011 -0.0562 1.3121 0.8272 -0.3129 0.0499 -0.4640 +1305031459.9094 -0.5059 -0.0532 1.3136 0.8272 -0.3132 0.0492 -0.4639 +1305031459.9194 -0.5104 -0.0504 1.3153 0.8274 -0.3138 0.0484 -0.4633 +1305031459.9294 -0.5152 -0.0471 1.3170 0.8271 -0.3148 0.0480 -0.4631 +1305031459.9394 -0.5198 -0.0440 1.3187 0.8273 -0.3159 0.0474 -0.4621 +1305031459.9493 -0.5244 -0.0407 1.3203 0.8267 -0.3172 0.0472 -0.4623 +1305031459.9594 -0.5288 -0.0375 1.3219 0.8273 -0.3183 0.0463 -0.4606 +1305031459.9694 -0.5333 -0.0342 1.3236 0.8274 -0.3197 0.0461 -0.4594 +1305031459.9794 -0.5377 -0.0309 1.3254 0.8280 -0.3206 0.0457 -0.4578 +1305031459.9895 -0.5421 -0.0276 1.3271 0.8280 -0.3219 0.0455 -0.4568 +1305031459.9994 -0.5464 -0.0243 1.3287 0.8279 -0.3230 0.0461 -0.4561 +1305031460.0094 -0.5506 -0.0209 1.3306 0.8278 -0.3237 0.0460 -0.4559 +1305031460.0193 -0.5546 -0.0176 1.3324 0.8275 -0.3247 0.0466 -0.4558 +1305031460.0294 -0.5584 -0.0141 1.3343 0.8275 -0.3250 0.0468 -0.4555 +1305031460.0394 -0.5624 -0.0104 1.3359 0.8267 -0.3259 0.0472 -0.4562 +1305031460.0494 -0.5660 -0.0070 1.3375 0.8267 -0.3267 0.0470 -0.4556 +1305031460.0597 -0.5698 -0.0034 1.3391 0.8263 -0.3272 0.0463 -0.4562 +1305031460.0694 -0.5733 0.0001 1.3407 0.8262 -0.3283 0.0446 -0.4557 +1305031460.0794 -0.5769 0.0036 1.3424 0.8255 -0.3299 0.0421 -0.4560 +1305031460.0893 -0.5799 0.0072 1.3440 0.8250 -0.3313 0.0393 -0.4561 +1305031460.0994 -0.5833 0.0109 1.3458 0.8241 -0.3332 0.0350 -0.4568 +1305031460.1094 -0.5861 0.0141 1.3475 0.8238 -0.3341 0.0320 -0.4569 +1305031460.1193 -0.5895 0.0180 1.3489 0.8220 -0.3366 0.0277 -0.4586 +1305031460.1294 -0.5923 0.0216 1.3506 0.8208 -0.3377 0.0248 -0.4601 +1305031460.1393 -0.5949 0.0247 1.3525 0.8205 -0.3395 0.0212 -0.4595 +1305031460.1493 -0.5974 0.0284 1.3540 0.8195 -0.3409 0.0186 -0.4603 +1305031460.1594 -0.5999 0.0318 1.3556 0.8197 -0.3425 0.0154 -0.4589 +1305031460.1693 -0.6022 0.0357 1.3570 0.8193 -0.3439 0.0126 -0.4586 +1305031460.1793 -0.6046 0.0391 1.3585 0.8199 -0.3450 0.0097 -0.4568 +1305031460.1894 -0.6069 0.0429 1.3600 0.8200 -0.3462 0.0082 -0.4557 +1305031460.1994 -0.6090 0.0465 1.3618 0.8198 -0.3473 0.0075 -0.4553 +1305031460.2094 -0.6111 0.0499 1.3633 0.8196 -0.3482 0.0075 -0.4550 +1305031460.2193 -0.6130 0.0534 1.3651 0.8187 -0.3496 0.0088 -0.4554 +1305031460.2294 -0.6148 0.0568 1.3667 0.8174 -0.3507 0.0106 -0.4569 +1305031460.2394 -0.6171 0.0601 1.3681 0.8156 -0.3536 0.0126 -0.4578 +1305031460.2494 -0.6189 0.0634 1.3698 0.8146 -0.3548 0.0154 -0.4586 +1305031460.2596 -0.6207 0.0666 1.3715 0.8140 -0.3560 0.0177 -0.4587 +1305031460.2694 -0.6221 0.0699 1.3731 0.8130 -0.3568 0.0210 -0.4596 +1305031460.2793 -0.6240 0.0731 1.3746 0.8130 -0.3580 0.0233 -0.4586 +1305031460.2893 -0.6254 0.0767 1.3764 0.8116 -0.3592 0.0263 -0.4600 +1305031460.2994 -0.6271 0.0799 1.3779 0.8111 -0.3604 0.0286 -0.4597 +1305031460.3094 -0.6285 0.0833 1.3797 0.8114 -0.3625 0.0299 -0.4575 +1305031460.3194 -0.6299 0.0869 1.3813 0.8106 -0.3645 0.0317 -0.4572 +1305031460.3294 -0.6313 0.0902 1.3827 0.8103 -0.3666 0.0334 -0.4560 +1305031460.3394 -0.6327 0.0940 1.3841 0.8091 -0.3689 0.0360 -0.4561 +1305031460.3494 -0.6340 0.0977 1.3854 0.8084 -0.3711 0.0381 -0.4554 +1305031460.3594 -0.6354 0.1012 1.3869 0.8079 -0.3737 0.0407 -0.4539 +1305031460.3698 -0.6367 0.1046 1.3882 0.8080 -0.3759 0.0432 -0.4515 +1305031460.3794 -0.6380 0.1082 1.3896 0.8075 -0.3784 0.0461 -0.4501 +1305031460.3894 -0.6392 0.1117 1.3909 0.8066 -0.3808 0.0491 -0.4494 +1305031460.3994 -0.6403 0.1154 1.3922 0.8056 -0.3834 0.0517 -0.4488 +1305031460.4094 -0.6414 0.1189 1.3935 0.8042 -0.3866 0.0543 -0.4481 +1305031460.4193 -0.6425 0.1223 1.3945 0.8031 -0.3893 0.0564 -0.4476 +1305031460.4294 -0.6436 0.1258 1.3957 0.8025 -0.3919 0.0589 -0.4461 +1305031460.4393 -0.6446 0.1292 1.3971 0.8012 -0.3953 0.0620 -0.4450 +1305031460.4494 -0.6456 0.1325 1.3983 0.7999 -0.3983 0.0657 -0.4440 +1305031460.4599 -0.6464 0.1360 1.3994 0.7985 -0.4017 0.0695 -0.4430 +1305031460.4694 -0.6474 0.1392 1.4006 0.7980 -0.4054 0.0731 -0.4399 +1305031460.4797 -0.6484 0.1425 1.4016 0.7971 -0.4095 0.0765 -0.4373 +1305031460.4894 -0.6496 0.1458 1.4027 0.7965 -0.4140 0.0789 -0.4336 +1305031460.4994 -0.6506 0.1492 1.4036 0.7955 -0.4183 0.0813 -0.4309 +1305031460.5094 -0.6518 0.1526 1.4046 0.7942 -0.4227 0.0834 -0.4284 +1305031460.5193 -0.6532 0.1557 1.4056 0.7936 -0.4261 0.0856 -0.4258 +1305031460.5294 -0.6544 0.1591 1.4066 0.7926 -0.4293 0.0881 -0.4239 +1305031460.5393 -0.6558 0.1623 1.4074 0.7924 -0.4314 0.0909 -0.4216 +1305031460.5493 -0.6572 0.1655 1.4083 0.7921 -0.4328 0.0938 -0.4201 +1305031460.5599 -0.6585 0.1688 1.4092 0.7914 -0.4341 0.0972 -0.4193 +1305031460.5693 -0.6599 0.1722 1.4099 0.7909 -0.4348 0.1007 -0.4187 +1305031460.5793 -0.6614 0.1754 1.4108 0.7903 -0.4367 0.1031 -0.4173 +1305031460.5893 -0.6630 0.1786 1.4116 0.7899 -0.4385 0.1054 -0.4156 +1305031460.5994 -0.6645 0.1819 1.4124 0.7890 -0.4405 0.1076 -0.4146 +1305031460.6094 -0.6660 0.1853 1.4132 0.7881 -0.4421 0.1102 -0.4139 +1305031460.6193 -0.6675 0.1885 1.4140 0.7872 -0.4432 0.1132 -0.4135 +1305031460.6294 -0.6691 0.1918 1.4148 0.7869 -0.4444 0.1154 -0.4123 +1305031460.6394 -0.6707 0.1953 1.4156 0.7864 -0.4450 0.1181 -0.4117 +1305031460.6495 -0.6722 0.1990 1.4163 0.7855 -0.4458 0.1208 -0.4118 +1305031460.6595 -0.6738 0.2024 1.4170 0.7855 -0.4471 0.1223 -0.4100 +1305031460.6693 -0.6755 0.2059 1.4177 0.7852 -0.4480 0.1238 -0.4092 +1305031460.6793 -0.6772 0.2095 1.4183 0.7849 -0.4490 0.1250 -0.4082 +1305031460.6894 -0.6789 0.2133 1.4188 0.7847 -0.4498 0.1259 -0.4075 +1305031460.6994 -0.6808 0.2170 1.4195 0.7854 -0.4505 0.1265 -0.4051 +1305031460.7094 -0.6826 0.2209 1.4199 0.7860 -0.4507 0.1274 -0.4036 +1305031460.7193 -0.6843 0.2247 1.4206 0.7863 -0.4511 0.1291 -0.4020 +1305031460.7294 -0.6860 0.2286 1.4211 0.7862 -0.4513 0.1312 -0.4012 +1305031460.7393 -0.6876 0.2323 1.4217 0.7863 -0.4512 0.1332 -0.4005 +1305031460.7494 -0.6890 0.2363 1.4223 0.7859 -0.4516 0.1356 -0.4000 +1305031460.7594 -0.6904 0.2403 1.4229 0.7857 -0.4520 0.1374 -0.3993 +1305031460.7693 -0.6919 0.2441 1.4235 0.7857 -0.4527 0.1392 -0.3979 +1305031460.7794 -0.6932 0.2483 1.4239 0.7856 -0.4528 0.1406 -0.3976 +1305031460.7894 -0.6947 0.2525 1.4244 0.7861 -0.4527 0.1416 -0.3964 +1305031460.7994 -0.6961 0.2569 1.4249 0.7868 -0.4526 0.1424 -0.3949 +1305031460.8093 -0.6973 0.2612 1.4254 0.7875 -0.4520 0.1434 -0.3936 +1305031460.8193 -0.6986 0.2654 1.4258 0.7884 -0.4516 0.1447 -0.3918 +1305031460.8294 -0.6998 0.2698 1.4264 0.7889 -0.4517 0.1463 -0.3900 +1305031460.8393 -0.7007 0.2742 1.4270 0.7897 -0.4516 0.1481 -0.3879 +1305031460.8494 -0.7019 0.2785 1.4276 0.7902 -0.4518 0.1501 -0.3859 +1305031460.8593 -0.7027 0.2828 1.4281 0.7907 -0.4514 0.1523 -0.3844 +1305031460.8694 -0.7034 0.2873 1.4286 0.7913 -0.4516 0.1549 -0.3820 +1305031460.8794 -0.7040 0.2919 1.4292 0.7917 -0.4513 0.1570 -0.3806 +1305031460.8893 -0.7047 0.2960 1.4298 0.7931 -0.4513 0.1578 -0.3773 +1305031460.8994 -0.7050 0.3005 1.4303 0.7935 -0.4510 0.1593 -0.3763 +1305031460.9094 -0.7053 0.3049 1.4309 0.7939 -0.4510 0.1604 -0.3749 +1305031460.9194 -0.7058 0.3093 1.4316 0.7946 -0.4519 0.1603 -0.3724 +1305031460.9294 -0.7060 0.3136 1.4322 0.7949 -0.4526 0.1602 -0.3710 +1305031460.9393 -0.7063 0.3178 1.4330 0.7953 -0.4533 0.1602 -0.3692 +1305031460.9494 -0.7063 0.3219 1.4340 0.7956 -0.4538 0.1605 -0.3680 +1305031460.9595 -0.7064 0.3262 1.4348 0.7950 -0.4543 0.1615 -0.3682 +1305031460.9701 -0.7062 0.3302 1.4358 0.7943 -0.4546 0.1630 -0.3687 +1305031460.9794 -0.7061 0.3343 1.4368 0.7931 -0.4552 0.1647 -0.3696 +1305031460.9894 -0.7060 0.3383 1.4377 0.7928 -0.4557 0.1653 -0.3693 +1305031460.9994 -0.7058 0.3423 1.4385 0.7925 -0.4561 0.1659 -0.3695 +1305031461.0094 -0.7056 0.3463 1.4394 0.7922 -0.4565 0.1660 -0.3693 +1305031461.0193 -0.7055 0.3501 1.4403 0.7917 -0.4570 0.1663 -0.3698 +1305031461.0294 -0.7053 0.3541 1.4411 0.7910 -0.4575 0.1667 -0.3705 +1305031461.0393 -0.7048 0.3579 1.4419 0.7900 -0.4574 0.1676 -0.3724 +1305031461.0493 -0.7047 0.3621 1.4427 0.7898 -0.4580 0.1673 -0.3722 +1305031461.0598 -0.7045 0.3661 1.4433 0.7902 -0.4579 0.1667 -0.3717 +1305031461.0693 -0.7041 0.3702 1.4438 0.7906 -0.4579 0.1661 -0.3711 +1305031461.0793 -0.7039 0.3742 1.4443 0.7918 -0.4574 0.1649 -0.3695 +1305031461.0893 -0.7037 0.3783 1.4448 0.7925 -0.4575 0.1647 -0.3682 +1305031461.0994 -0.7032 0.3823 1.4453 0.7929 -0.4567 0.1649 -0.3681 +1305031461.1093 -0.7028 0.3863 1.4458 0.7931 -0.4560 0.1661 -0.3680 +1305031461.1193 -0.7023 0.3900 1.4464 0.7931 -0.4557 0.1670 -0.3680 +1305031461.1294 -0.7019 0.3937 1.4472 0.7936 -0.4556 0.1670 -0.3671 +1305031461.1393 -0.7014 0.3972 1.4478 0.7932 -0.4552 0.1678 -0.3680 +1305031461.1493 -0.7009 0.4008 1.4484 0.7930 -0.4546 0.1683 -0.3689 +1305031461.1593 -0.7004 0.4044 1.4489 0.7926 -0.4537 0.1694 -0.3706 +1305031461.1693 -0.6999 0.4078 1.4493 0.7927 -0.4527 0.1699 -0.3713 +1305031461.1793 -0.6995 0.4111 1.4497 0.7930 -0.4516 0.1702 -0.3717 +1305031461.1893 -0.6988 0.4143 1.4501 0.7928 -0.4509 0.1713 -0.3727 +1305031461.1993 -0.6984 0.4172 1.4502 0.7934 -0.4503 0.1716 -0.3718 +1305031461.2096 -0.6977 0.4200 1.4504 0.7931 -0.4497 0.1730 -0.3725 +1305031461.2193 -0.6973 0.4229 1.4505 0.7934 -0.4495 0.1733 -0.3721 +1305031461.2293 -0.6969 0.4257 1.4507 0.7937 -0.4492 0.1731 -0.3720 +1305031461.2393 -0.6965 0.4286 1.4507 0.7937 -0.4487 0.1733 -0.3725 +1305031461.2494 -0.6961 0.4315 1.4505 0.7936 -0.4467 0.1748 -0.3743 +1305031461.2593 -0.6954 0.4340 1.4505 0.7931 -0.4454 0.1761 -0.3762 +1305031461.2693 -0.6951 0.4367 1.4503 0.7938 -0.4437 0.1767 -0.3765 +1305031461.2793 -0.6946 0.4392 1.4501 0.7944 -0.4422 0.1775 -0.3768 +1305031461.2894 -0.6937 0.4420 1.4498 0.7944 -0.4410 0.1784 -0.3775 +1305031461.2994 -0.6928 0.4450 1.4495 0.7943 -0.4399 0.1799 -0.3784 +1305031461.3094 -0.6919 0.4479 1.4492 0.7948 -0.4398 0.1804 -0.3773 +1305031461.3193 -0.6908 0.4508 1.4488 0.7948 -0.4387 0.1819 -0.3778 +1305031461.3294 -0.6893 0.4538 1.4483 0.7948 -0.4384 0.1839 -0.3772 +1305031461.3393 -0.6879 0.4567 1.4478 0.7954 -0.4377 0.1858 -0.3758 +1305031461.3493 -0.6864 0.4595 1.4473 0.7962 -0.4376 0.1869 -0.3738 +1305031461.3593 -0.6851 0.4623 1.4467 0.7977 -0.4376 0.1872 -0.3704 +1305031461.3693 -0.6837 0.4650 1.4461 0.7988 -0.4379 0.1875 -0.3675 +1305031461.3793 -0.6823 0.4676 1.4457 0.7993 -0.4378 0.1875 -0.3665 +1305031461.3893 -0.6808 0.4701 1.4453 0.8001 -0.4378 0.1871 -0.3650 +1305031461.3994 -0.6793 0.4724 1.4452 0.7999 -0.4374 0.1880 -0.3653 +1305031461.4095 -0.6776 0.4748 1.4451 0.7994 -0.4368 0.1893 -0.3664 +1305031461.4193 -0.6760 0.4768 1.4448 0.7994 -0.4363 0.1897 -0.3669 +1305031461.4294 -0.6746 0.4784 1.4448 0.8002 -0.4364 0.1895 -0.3651 +1305031461.4393 -0.6731 0.4801 1.4446 0.8006 -0.4371 0.1895 -0.3633 +1305031461.4494 -0.6716 0.4817 1.4443 0.8013 -0.4381 0.1886 -0.3610 +1305031461.4593 -0.6701 0.4827 1.4441 0.8022 -0.4389 0.1876 -0.3587 +1305031461.4693 -0.6688 0.4839 1.4441 0.8028 -0.4394 0.1872 -0.3569 +1305031461.4793 -0.6674 0.4849 1.4442 0.8024 -0.4390 0.1880 -0.3579 +1305031461.4893 -0.6661 0.4858 1.4446 0.8018 -0.4387 0.1890 -0.3590 +1305031461.4994 -0.6647 0.4865 1.4450 0.8014 -0.4378 0.1895 -0.3609 +1305031461.5093 -0.6633 0.4869 1.4454 0.8004 -0.4374 0.1903 -0.3629 +1305031461.5193 -0.6619 0.4871 1.4459 0.8004 -0.4370 0.1903 -0.3635 +1305031461.5293 -0.6605 0.4875 1.4460 0.7999 -0.4368 0.1910 -0.3645 +1305031461.5394 -0.6594 0.4874 1.4463 0.8007 -0.4364 0.1913 -0.3631 +1305031461.5494 -0.6582 0.4871 1.4465 0.8014 -0.4360 0.1919 -0.3617 +1305031461.5593 -0.6568 0.4867 1.4469 0.8008 -0.4353 0.1947 -0.3625 +1305031461.5693 -0.6553 0.4862 1.4472 0.8007 -0.4347 0.1972 -0.3620 +1305031461.5794 -0.6535 0.4856 1.4474 0.7995 -0.4345 0.2002 -0.3631 +1305031461.5893 -0.6519 0.4851 1.4475 0.7990 -0.4348 0.2023 -0.3627 +1305031461.5993 -0.6502 0.4842 1.4477 0.7988 -0.4358 0.2036 -0.3614 +1305031461.6096 -0.6485 0.4835 1.4479 0.7987 -0.4366 0.2046 -0.3601 +1305031461.6193 -0.6469 0.4826 1.4477 0.7989 -0.4368 0.2057 -0.3585 +1305031461.6293 -0.6450 0.4814 1.4476 0.7990 -0.4368 0.2073 -0.3577 +1305031461.6393 -0.6430 0.4801 1.4474 0.7988 -0.4369 0.2081 -0.3573 +1305031461.6494 -0.6412 0.4788 1.4471 0.7988 -0.4373 0.2088 -0.3565 +1305031461.6594 -0.6392 0.4775 1.4467 0.7980 -0.4381 0.2097 -0.3567 +1305031461.6694 -0.6372 0.4757 1.4465 0.7975 -0.4397 0.2098 -0.3559 +1305031461.6793 -0.6354 0.4738 1.4460 0.7972 -0.4421 0.2089 -0.3541 +1305031461.6894 -0.6334 0.4721 1.4453 0.7964 -0.4440 0.2084 -0.3539 +1305031461.6994 -0.6320 0.4700 1.4448 0.7966 -0.4460 0.2068 -0.3518 +1305031461.7094 -0.6302 0.4679 1.4440 0.7960 -0.4478 0.2064 -0.3511 +1305031461.7193 -0.6286 0.4656 1.4434 0.7956 -0.4486 0.2063 -0.3511 +1305031461.7293 -0.6272 0.4633 1.4426 0.7949 -0.4494 0.2062 -0.3516 +1305031461.7393 -0.6256 0.4610 1.4419 0.7943 -0.4502 0.2067 -0.3517 +1305031461.7494 -0.6242 0.4583 1.4410 0.7937 -0.4512 0.2070 -0.3515 +1305031461.7593 -0.6227 0.4558 1.4397 0.7932 -0.4523 0.2074 -0.3511 +1305031461.7694 -0.6216 0.4529 1.4386 0.7933 -0.4540 0.2069 -0.3490 +1305031461.7793 -0.6203 0.4498 1.4373 0.7930 -0.4556 0.2065 -0.3476 +1305031461.7893 -0.6190 0.4467 1.4358 0.7925 -0.4570 0.2073 -0.3465 +1305031461.7994 -0.6177 0.4436 1.4345 0.7918 -0.4585 0.2076 -0.3460 +1305031461.8093 -0.6165 0.4399 1.4330 0.7908 -0.4601 0.2083 -0.3457 +1305031461.8193 -0.6154 0.4366 1.4315 0.7894 -0.4619 0.2093 -0.3459 +1305031461.8293 -0.6140 0.4331 1.4299 0.7882 -0.4639 0.2097 -0.3458 +1305031461.8393 -0.6127 0.4292 1.4281 0.7870 -0.4660 0.2100 -0.3455 +1305031461.8494 -0.6114 0.4253 1.4262 0.7857 -0.4687 0.2099 -0.3449 +1305031461.8593 -0.6103 0.4212 1.4241 0.7850 -0.4718 0.2091 -0.3428 +1305031461.8693 -0.6090 0.4175 1.4219 0.7834 -0.4751 0.2084 -0.3422 +1305031461.8793 -0.6079 0.4136 1.4197 0.7826 -0.4788 0.2067 -0.3398 +1305031461.8893 -0.6068 0.4097 1.4172 0.7821 -0.4819 0.2048 -0.3379 +1305031461.8994 -0.6062 0.4062 1.4150 0.7818 -0.4848 0.2025 -0.3357 +1305031461.9094 -0.6054 0.4025 1.4126 0.7814 -0.4874 0.2006 -0.3340 +1305031461.9193 -0.6047 0.3987 1.4102 0.7814 -0.4888 0.1993 -0.3329 +1305031461.9293 -0.6041 0.3949 1.4080 0.7808 -0.4899 0.1995 -0.3326 +1305031461.9393 -0.6036 0.3910 1.4059 0.7800 -0.4913 0.2009 -0.3314 +1305031461.9494 -0.6029 0.3871 1.4037 0.7790 -0.4927 0.2028 -0.3305 +1305031461.9593 -0.6022 0.3831 1.4014 0.7779 -0.4944 0.2050 -0.3292 +1305031461.9693 -0.6018 0.3792 1.3992 0.7771 -0.4976 0.2060 -0.3257 +1305031461.9793 -0.6013 0.3754 1.3967 0.7764 -0.5007 0.2062 -0.3224 +1305031461.9893 -0.6010 0.3714 1.3942 0.7763 -0.5035 0.2053 -0.3187 +1305031461.9993 -0.6007 0.3677 1.3916 0.7761 -0.5065 0.2039 -0.3155 +1305031462.0093 -0.6004 0.3641 1.3893 0.7761 -0.5089 0.2016 -0.3130 +1305031462.0193 -0.6001 0.3606 1.3868 0.7756 -0.5115 0.1995 -0.3115 +1305031462.0293 -0.5999 0.3572 1.3844 0.7750 -0.5139 0.1968 -0.3106 +1305031462.0393 -0.5999 0.3539 1.3821 0.7743 -0.5165 0.1938 -0.3101 +1305031462.0494 -0.5999 0.3508 1.3799 0.7735 -0.5194 0.1904 -0.3094 +1305031462.0593 -0.6001 0.3475 1.3778 0.7727 -0.5224 0.1865 -0.3086 +1305031462.0693 -0.6001 0.3447 1.3757 0.7716 -0.5249 0.1838 -0.3088 +1305031462.0793 -0.6004 0.3416 1.3736 0.7707 -0.5274 0.1809 -0.3083 +1305031462.0893 -0.6008 0.3388 1.3717 0.7704 -0.5296 0.1781 -0.3071 +1305031462.0993 -0.6014 0.3357 1.3698 0.7698 -0.5318 0.1760 -0.3059 +1305031462.1093 -0.6018 0.3329 1.3677 0.7690 -0.5337 0.1748 -0.3054 +1305031462.1193 -0.6025 0.3304 1.3657 0.7682 -0.5362 0.1731 -0.3041 +1305031462.1293 -0.6033 0.3277 1.3639 0.7673 -0.5381 0.1721 -0.3034 +1305031462.1393 -0.6043 0.3252 1.3621 0.7672 -0.5394 0.1703 -0.3024 +1305031462.1493 -0.6053 0.3228 1.3605 0.7674 -0.5405 0.1687 -0.3009 +1305031462.1593 -0.6060 0.3207 1.3586 0.7668 -0.5410 0.1689 -0.3014 +1305031462.1693 -0.6072 0.3187 1.3568 0.7673 -0.5407 0.1693 -0.3002 +1305031462.1793 -0.6082 0.3166 1.3550 0.7679 -0.5400 0.1697 -0.3000 +1305031462.1893 -0.6096 0.3145 1.3532 0.7683 -0.5404 0.1697 -0.2982 +1305031462.1993 -0.6107 0.3125 1.3513 0.7684 -0.5405 0.1705 -0.2973 +1305031462.2093 -0.6121 0.3103 1.3494 0.7689 -0.5409 0.1705 -0.2952 +1305031462.2193 -0.6132 0.3083 1.3475 0.7699 -0.5411 0.1696 -0.2928 +1305031462.2293 -0.6147 0.3065 1.3455 0.7704 -0.5407 0.1704 -0.2918 +1305031462.2393 -0.6158 0.3045 1.3436 0.7719 -0.5396 0.1701 -0.2900 +1305031462.2493 -0.6171 0.3030 1.3417 0.7725 -0.5390 0.1705 -0.2892 +1305031462.2593 -0.6188 0.3009 1.3397 0.7748 -0.5370 0.1697 -0.2872 +1305031462.2694 -0.6203 0.2991 1.3376 0.7765 -0.5354 0.1696 -0.2856 +1305031462.2793 -0.6217 0.2973 1.3354 0.7777 -0.5337 0.1696 -0.2856 +1305031462.2894 -0.6236 0.2952 1.3335 0.7803 -0.5320 0.1684 -0.2825 +1305031462.2993 -0.6251 0.2935 1.3312 0.7813 -0.5307 0.1688 -0.2818 +1305031462.3093 -0.6267 0.2916 1.3292 0.7828 -0.5290 0.1694 -0.2805 +1305031462.3193 -0.6284 0.2896 1.3271 0.7844 -0.5274 0.1696 -0.2789 +1305031462.3293 -0.6299 0.2877 1.3249 0.7862 -0.5251 0.1705 -0.2776 +1305031462.3393 -0.6318 0.2858 1.3226 0.7881 -0.5229 0.1712 -0.2758 +1305031462.3494 -0.6334 0.2837 1.3204 0.7904 -0.5206 0.1712 -0.2737 +1305031462.3594 -0.6350 0.2818 1.3179 0.7923 -0.5184 0.1712 -0.2724 +1305031462.3693 -0.6368 0.2800 1.3154 0.7947 -0.5164 0.1701 -0.2700 +1305031462.3794 -0.6388 0.2781 1.3131 0.7969 -0.5147 0.1687 -0.2677 +1305031462.3893 -0.6406 0.2761 1.3106 0.7988 -0.5125 0.1678 -0.2664 +1305031462.3993 -0.6426 0.2739 1.3083 0.8012 -0.5104 0.1665 -0.2644 +1305031462.4093 -0.6448 0.2719 1.3059 0.8036 -0.5082 0.1655 -0.2620 +1305031462.4193 -0.6469 0.2698 1.3037 0.8056 -0.5058 0.1645 -0.2609 +1305031462.4293 -0.6490 0.2675 1.3013 0.8079 -0.5031 0.1631 -0.2601 +1305031462.4393 -0.6514 0.2653 1.2993 0.8108 -0.5004 0.1607 -0.2577 +1305031462.4494 -0.6534 0.2630 1.2970 0.8133 -0.4977 0.1593 -0.2560 +1305031462.4594 -0.6557 0.2607 1.2948 0.8158 -0.4949 0.1583 -0.2539 +1305031462.4693 -0.6578 0.2583 1.2927 0.8182 -0.4926 0.1564 -0.2517 +1305031462.4793 -0.6599 0.2558 1.2908 0.8205 -0.4905 0.1548 -0.2493 +1305031462.4893 -0.6622 0.2532 1.2890 0.8228 -0.4880 0.1532 -0.2479 +1305031462.4993 -0.6644 0.2507 1.2873 0.8244 -0.4860 0.1520 -0.2471 +1305031462.5093 -0.6664 0.2483 1.2858 0.8263 -0.4836 0.1499 -0.2466 +1305031462.5193 -0.6686 0.2458 1.2843 0.8282 -0.4807 0.1483 -0.2469 +1305031462.5293 -0.6707 0.2430 1.2830 0.8302 -0.4777 0.1469 -0.2470 +1305031462.5393 -0.6728 0.2402 1.2819 0.8327 -0.4744 0.1448 -0.2463 +1305031462.5493 -0.6749 0.2376 1.2807 0.8343 -0.4716 0.1441 -0.2466 +1305031462.5593 -0.6768 0.2348 1.2796 0.8359 -0.4682 0.1445 -0.2473 +1305031462.5696 -0.6789 0.2318 1.2789 0.8378 -0.4652 0.1444 -0.2466 +1305031462.5794 -0.6810 0.2289 1.2782 0.8394 -0.4618 0.1451 -0.2472 +1305031462.5893 -0.6825 0.2262 1.2775 0.8408 -0.4587 0.1454 -0.2481 +1305031462.5993 -0.6843 0.2233 1.2769 0.8425 -0.4556 0.1454 -0.2480 +1305031462.6094 -0.6859 0.2201 1.2764 0.8444 -0.4520 0.1457 -0.2481 +1305031462.6193 -0.6876 0.2170 1.2760 0.8458 -0.4486 0.1467 -0.2488 +1305031462.6293 -0.6892 0.2137 1.2758 0.8473 -0.4456 0.1468 -0.2489 +1305031462.6394 -0.6907 0.2103 1.2755 0.8487 -0.4420 0.1479 -0.2500 +1305031462.6493 -0.6920 0.2068 1.2753 0.8497 -0.4384 0.1493 -0.2520 +1305031462.6593 -0.6936 0.2033 1.2754 0.8512 -0.4353 0.1491 -0.2525 +1305031462.6693 -0.6949 0.1998 1.2752 0.8520 -0.4318 0.1502 -0.2552 +1305031462.6793 -0.6963 0.1959 1.2751 0.8538 -0.4281 0.1496 -0.2558 +1305031462.6893 -0.6976 0.1923 1.2751 0.8554 -0.4244 0.1491 -0.2568 +1305031462.6993 -0.6989 0.1885 1.2749 0.8573 -0.4205 0.1483 -0.2574 +1305031462.7093 -0.7001 0.1846 1.2747 0.8593 -0.4163 0.1471 -0.2581 +1305031462.7193 -0.7010 0.1807 1.2745 0.8613 -0.4120 0.1461 -0.2589 +1305031462.7293 -0.7020 0.1767 1.2745 0.8631 -0.4079 0.1450 -0.2600 +1305031462.7393 -0.7029 0.1724 1.2742 0.8651 -0.4038 0.1437 -0.2605 +1305031462.7493 -0.7037 0.1681 1.2741 0.8668 -0.4002 0.1429 -0.2610 +1305031462.7593 -0.7044 0.1634 1.2739 0.8682 -0.3966 0.1424 -0.2620 +1305031462.7693 -0.7047 0.1589 1.2738 0.8693 -0.3935 0.1419 -0.2633 +1305031462.7793 -0.7053 0.1540 1.2738 0.8708 -0.3908 0.1407 -0.2629 +1305031462.7893 -0.7056 0.1492 1.2739 0.8721 -0.3882 0.1391 -0.2634 +1305031462.7993 -0.7056 0.1442 1.2739 0.8735 -0.3857 0.1380 -0.2631 +1305031462.8096 -0.7057 0.1391 1.2736 0.8744 -0.3833 0.1366 -0.2644 +1305031462.8193 -0.7057 0.1340 1.2737 0.8757 -0.3811 0.1354 -0.2637 +1305031462.8293 -0.7054 0.1287 1.2737 0.8769 -0.3793 0.1338 -0.2631 +1305031462.8394 -0.7053 0.1232 1.2740 0.8785 -0.3771 0.1324 -0.2617 +1305031462.8494 -0.7048 0.1178 1.2740 0.8790 -0.3752 0.1323 -0.2628 +1305031462.8593 -0.7043 0.1122 1.2743 0.8797 -0.3737 0.1321 -0.2626 +1305031462.8693 -0.7036 0.1067 1.2746 0.8799 -0.3726 0.1325 -0.2633 +1305031462.8793 -0.7028 0.1008 1.2750 0.8805 -0.3712 0.1322 -0.2635 +1305031462.8893 -0.7019 0.0952 1.2753 0.8806 -0.3702 0.1323 -0.2647 +1305031462.8993 -0.7009 0.0896 1.2757 0.8809 -0.3691 0.1323 -0.2650 +1305031462.9093 -0.6998 0.0838 1.2763 0.8813 -0.3686 0.1313 -0.2651 +1305031462.9193 -0.6986 0.0783 1.2767 0.8814 -0.3669 0.1313 -0.2668 +1305031462.9294 -0.6975 0.0727 1.2774 0.8819 -0.3659 0.1304 -0.2670 +1305031462.9393 -0.6964 0.0672 1.2780 0.8827 -0.3645 0.1292 -0.2671 +1305031462.9494 -0.6950 0.0619 1.2785 0.8829 -0.3626 0.1286 -0.2694 +1305031462.9593 -0.6939 0.0564 1.2793 0.8835 -0.3610 0.1267 -0.2701 +1305031462.9693 -0.6925 0.0511 1.2802 0.8834 -0.3595 0.1265 -0.2726 +1305031462.9794 -0.6909 0.0456 1.2812 0.8837 -0.3566 0.1261 -0.2758 +1305031462.9893 -0.6897 0.0405 1.2822 0.8842 -0.3542 0.1249 -0.2777 +1305031462.9993 -0.6884 0.0352 1.2835 0.8845 -0.3518 0.1247 -0.2798 +1305031463.0093 -0.6870 0.0299 1.2848 0.8848 -0.3491 0.1239 -0.2825 +1305031463.0193 -0.6855 0.0249 1.2858 0.8849 -0.3464 0.1237 -0.2857 +1305031463.0294 -0.6841 0.0198 1.2871 0.8856 -0.3433 0.1224 -0.2878 +1305031463.0393 -0.6825 0.0147 1.2883 0.8864 -0.3402 0.1209 -0.2898 +1305031463.0493 -0.6810 0.0098 1.2894 0.8875 -0.3373 0.1194 -0.2905 +1305031463.0593 -0.6792 0.0047 1.2905 0.8882 -0.3340 0.1189 -0.2923 +1305031463.0735 -0.6777 -0.0004 1.2918 0.8896 -0.3315 0.1174 -0.2916 +1305031463.0793 -0.6761 -0.0053 1.2931 0.8904 -0.3283 0.1173 -0.2927 +1305031463.0894 -0.6744 -0.0103 1.2945 0.8911 -0.3253 0.1177 -0.2935 +1305031463.0993 -0.6726 -0.0151 1.2959 0.8917 -0.3220 0.1177 -0.2955 +1305031463.1094 -0.6709 -0.0201 1.2975 0.8919 -0.3188 0.1186 -0.2980 +1305031463.1194 -0.6689 -0.0247 1.2988 0.8923 -0.3156 0.1186 -0.3002 +1305031463.1293 -0.6670 -0.0295 1.3004 0.8928 -0.3125 0.1183 -0.3019 +1305031463.1393 -0.6650 -0.0343 1.3016 0.8931 -0.3099 0.1183 -0.3040 +1305031463.1493 -0.6629 -0.0389 1.3027 0.8936 -0.3070 0.1183 -0.3053 +1305031463.1593 -0.6606 -0.0434 1.3039 0.8938 -0.3045 0.1184 -0.3071 +1305031463.1694 -0.6584 -0.0480 1.3051 0.8947 -0.3021 0.1186 -0.3067 +1305031463.1794 -0.6560 -0.0525 1.3060 0.8956 -0.3000 0.1184 -0.3065 +1305031463.1893 -0.6536 -0.0569 1.3069 0.8965 -0.2979 0.1182 -0.3059 +1305031463.1994 -0.6511 -0.0614 1.3081 0.8978 -0.2959 0.1171 -0.3045 +1305031463.2093 -0.6485 -0.0656 1.3090 0.8976 -0.2945 0.1172 -0.3063 +1305031463.2194 -0.6456 -0.0700 1.3100 0.8977 -0.2925 0.1176 -0.3077 +1305031463.2294 -0.6429 -0.0742 1.3112 0.8975 -0.2912 0.1171 -0.3098 +1305031463.2393 -0.6400 -0.0784 1.3121 0.8970 -0.2900 0.1168 -0.3123 +1305031463.2493 -0.6371 -0.0826 1.3131 0.8968 -0.2890 0.1169 -0.3140 +1305031463.2593 -0.6340 -0.0868 1.3141 0.8967 -0.2870 0.1175 -0.3158 +1305031463.2693 -0.6308 -0.0905 1.3149 0.8967 -0.2850 0.1174 -0.3177 +1305031463.2793 -0.6277 -0.0945 1.3155 0.8973 -0.2832 0.1169 -0.3176 +1305031463.2893 -0.6245 -0.0984 1.3162 0.8981 -0.2814 0.1166 -0.3174 +1305031463.2993 -0.6212 -0.1023 1.3170 0.8992 -0.2795 0.1151 -0.3162 +1305031463.3093 -0.6181 -0.1061 1.3177 0.8997 -0.2779 0.1141 -0.3166 +1305031463.3193 -0.6147 -0.1098 1.3182 0.8999 -0.2762 0.1128 -0.3182 +1305031463.3293 -0.6112 -0.1133 1.3190 0.8998 -0.2746 0.1118 -0.3201 +1305031463.3393 -0.6077 -0.1169 1.3198 0.8995 -0.2732 0.1105 -0.3225 +1305031463.3493 -0.6041 -0.1206 1.3205 0.8996 -0.2717 0.1086 -0.3242 +1305031463.3593 -0.6004 -0.1240 1.3209 0.8993 -0.2701 0.1075 -0.3269 +1305031463.3693 -0.5967 -0.1274 1.3216 0.8990 -0.2686 0.1062 -0.3290 +1305031463.3793 -0.5929 -0.1309 1.3219 0.8996 -0.2670 0.1045 -0.3294 +1305031463.3894 -0.5890 -0.1344 1.3226 0.9002 -0.2655 0.1034 -0.3292 +1305031463.3994 -0.5851 -0.1378 1.3232 0.9007 -0.2641 0.1030 -0.3294 +1305031463.4093 -0.5811 -0.1412 1.3237 0.9010 -0.2628 0.1021 -0.3297 +1305031463.4193 -0.5770 -0.1446 1.3243 0.9015 -0.2614 0.1013 -0.3298 +1305031463.4293 -0.5728 -0.1480 1.3249 0.9017 -0.2608 0.1006 -0.3299 +1305031463.4393 -0.5685 -0.1516 1.3255 0.9019 -0.2601 0.1002 -0.3300 +1305031463.4494 -0.5642 -0.1549 1.3260 0.9018 -0.2597 0.1000 -0.3306 +1305031463.4596 -0.5598 -0.1583 1.3267 0.9020 -0.2595 0.1001 -0.3303 +1305031463.4693 -0.5552 -0.1619 1.3272 0.9022 -0.2590 0.1003 -0.3300 +1305031463.4793 -0.5508 -0.1653 1.3280 0.9024 -0.2589 0.1010 -0.3294 +1305031463.4893 -0.5463 -0.1688 1.3288 0.9024 -0.2584 0.1020 -0.3293 +1305031463.4993 -0.5417 -0.1721 1.3297 0.9021 -0.2580 0.1030 -0.3301 +1305031463.5093 -0.5370 -0.1755 1.3308 0.9015 -0.2577 0.1046 -0.3315 +1305031463.5193 -0.5324 -0.1790 1.3320 0.9015 -0.2572 0.1052 -0.3318 +1305031463.5294 -0.5280 -0.1827 1.3333 0.9013 -0.2576 0.1053 -0.3321 +1305031463.5393 -0.5234 -0.1859 1.3344 0.9005 -0.2578 0.1055 -0.3338 +1305031463.5494 -0.5188 -0.1894 1.3356 0.9002 -0.2575 0.1055 -0.3351 +1305031463.5593 -0.5143 -0.1928 1.3370 0.9005 -0.2575 0.1043 -0.3346 +1305031463.5694 -0.5098 -0.1960 1.3383 0.9007 -0.2571 0.1029 -0.3347 +1305031463.5793 -0.5052 -0.1995 1.3398 0.9013 -0.2567 0.1016 -0.3337 +1305031463.5894 -0.5005 -0.2028 1.3413 0.9018 -0.2558 0.1006 -0.3336 +1305031463.5993 -0.4957 -0.2059 1.3431 0.9019 -0.2548 0.0998 -0.3344 +1305031463.6093 -0.4910 -0.2093 1.3451 0.9017 -0.2539 0.0995 -0.3355 +1305031463.6193 -0.4863 -0.2128 1.3475 0.9021 -0.2534 0.0983 -0.3351 +1305031463.6294 -0.4812 -0.2157 1.3496 0.9004 -0.2525 0.0997 -0.3400 +1305031463.6393 -0.4762 -0.2191 1.3522 0.8996 -0.2518 0.1001 -0.3425 +1305031463.6494 -0.4713 -0.2222 1.3548 0.8991 -0.2511 0.0994 -0.3445 +1305031463.6593 -0.4663 -0.2252 1.3572 0.8982 -0.2503 0.0997 -0.3474 +1305031463.6693 -0.4613 -0.2285 1.3600 0.8983 -0.2492 0.0989 -0.3481 +1305031463.6793 -0.4563 -0.2316 1.3627 0.8990 -0.2485 0.0979 -0.3471 +1305031463.6893 -0.4512 -0.2346 1.3654 0.8995 -0.2471 0.0977 -0.3469 +1305031463.6993 -0.4460 -0.2376 1.3682 0.8998 -0.2460 0.0973 -0.3471 +1305031463.7093 -0.4407 -0.2405 1.3715 0.9004 -0.2449 0.0976 -0.3461 +1305031463.7193 -0.4353 -0.2432 1.3750 0.9002 -0.2438 0.0981 -0.3473 +1305031463.7293 -0.4298 -0.2461 1.3786 0.9000 -0.2423 0.0990 -0.3485 +1305031463.7393 -0.4244 -0.2486 1.3823 0.8992 -0.2411 0.1004 -0.3510 +1305031463.7494 -0.4190 -0.2513 1.3864 0.8987 -0.2394 0.1013 -0.3533 +1305031463.7594 -0.4137 -0.2537 1.3904 0.8986 -0.2370 0.1022 -0.3549 +1305031463.7694 -0.4083 -0.2563 1.3946 0.8985 -0.2347 0.1033 -0.3562 +1305031463.7794 -0.4029 -0.2586 1.3987 0.8984 -0.2317 0.1047 -0.3582 +1305031463.7893 -0.3975 -0.2611 1.4028 0.8990 -0.2285 0.1056 -0.3584 +1305031463.7998 -0.3924 -0.2633 1.4072 0.8996 -0.2258 0.1065 -0.3583 +1305031463.8093 -0.3872 -0.2658 1.4116 0.9005 -0.2226 0.1072 -0.3579 +1305031463.8193 -0.3820 -0.2681 1.4161 0.9008 -0.2203 0.1083 -0.3581 +1305031463.8293 -0.3769 -0.2706 1.4208 0.9014 -0.2173 0.1095 -0.3582 +1305031463.8393 -0.3717 -0.2726 1.4254 0.9011 -0.2146 0.1107 -0.3600 +1305031463.8493 -0.3666 -0.2749 1.4303 0.9012 -0.2117 0.1121 -0.3611 +1305031463.8593 -0.3614 -0.2770 1.4351 0.9009 -0.2089 0.1135 -0.3632 +1305031463.8694 -0.3565 -0.2791 1.4401 0.9010 -0.2068 0.1144 -0.3639 +1305031463.8793 -0.3514 -0.2815 1.4448 0.9016 -0.2042 0.1152 -0.3636 +1305031463.8893 -0.3464 -0.2833 1.4495 0.9014 -0.2017 0.1158 -0.3652 +1305031463.8993 -0.3416 -0.2853 1.4544 0.9022 -0.2001 0.1156 -0.3643 +1305031463.9093 -0.3370 -0.2873 1.4593 0.9027 -0.1979 0.1152 -0.3643 +1305031463.9193 -0.3324 -0.2892 1.4641 0.9029 -0.1960 0.1146 -0.3650 +1305031463.9293 -0.3278 -0.2911 1.4690 0.9032 -0.1935 0.1138 -0.3658 +1305031463.9393 -0.3234 -0.2930 1.4739 0.9036 -0.1912 0.1130 -0.3663 +1305031463.9494 -0.3191 -0.2950 1.4790 0.9038 -0.1888 0.1122 -0.3674 +1305031463.9593 -0.3149 -0.2969 1.4838 0.9033 -0.1866 0.1121 -0.3695 +1305031463.9693 -0.3110 -0.2989 1.4890 0.9037 -0.1846 0.1114 -0.3698 +1305031463.9793 -0.3069 -0.3009 1.4939 0.9038 -0.1818 0.1112 -0.3711 +1305031463.9893 -0.3030 -0.3026 1.4989 0.9037 -0.1796 0.1109 -0.3725 +1305031463.9993 -0.2992 -0.3045 1.5038 0.9038 -0.1768 0.1107 -0.3737 +1305031464.0093 -0.2955 -0.3063 1.5087 0.9044 -0.1739 0.1104 -0.3738 +1305031464.0193 -0.2919 -0.3082 1.5136 0.9051 -0.1713 0.1108 -0.3732 +1305031464.0293 -0.2883 -0.3101 1.5187 0.9056 -0.1692 0.1108 -0.3728 +1305031464.0393 -0.2850 -0.3119 1.5236 0.9057 -0.1667 0.1114 -0.3736 +1305031464.0494 -0.2816 -0.3136 1.5287 0.9056 -0.1641 0.1128 -0.3744 +1305031464.0593 -0.2782 -0.3152 1.5337 0.9053 -0.1612 0.1140 -0.3761 +1305031464.0693 -0.2750 -0.3171 1.5388 0.9052 -0.1587 0.1153 -0.3770 +1305031464.0793 -0.2717 -0.3187 1.5439 0.9047 -0.1558 0.1166 -0.3791 +1305031464.0893 -0.2687 -0.3204 1.5490 0.9046 -0.1538 0.1174 -0.3798 +1305031464.0993 -0.2656 -0.3223 1.5540 0.9046 -0.1517 0.1179 -0.3805 +1305031464.1093 -0.2627 -0.3241 1.5589 0.9048 -0.1498 0.1175 -0.3809 +1305031464.1193 -0.2598 -0.3259 1.5639 0.9049 -0.1485 0.1165 -0.3816 +1305031464.1293 -0.2570 -0.3277 1.5688 0.9048 -0.1475 0.1156 -0.3825 +1305031464.1393 -0.2543 -0.3294 1.5736 0.9042 -0.1466 0.1142 -0.3844 +1305031464.1494 -0.2517 -0.3313 1.5785 0.9043 -0.1453 0.1123 -0.3853 +1305031464.1593 -0.2491 -0.3331 1.5834 0.9039 -0.1438 0.1104 -0.3874 +1305031464.1693 -0.2464 -0.3349 1.5881 0.9027 -0.1418 0.1086 -0.3915 +1305031464.1794 -0.2438 -0.3368 1.5928 0.9022 -0.1397 0.1064 -0.3939 +1305031464.1893 -0.2414 -0.3387 1.5975 0.9015 -0.1371 0.1039 -0.3971 +1305031464.1993 -0.2386 -0.3403 1.6018 0.9006 -0.1346 0.1015 -0.4007 +1305031464.2093 -0.2359 -0.3421 1.6060 0.9003 -0.1320 0.0985 -0.4028 +1305031464.2193 -0.2332 -0.3437 1.6102 0.8995 -0.1296 0.0952 -0.4061 +1305031464.2293 -0.2310 -0.3459 1.6142 0.9002 -0.1274 0.0909 -0.4064 +1305031464.2393 -0.2282 -0.3473 1.6177 0.8995 -0.1258 0.0871 -0.4093 +1305031464.2493 -0.2256 -0.3493 1.6212 0.8999 -0.1230 0.0824 -0.4101 +1305031464.2593 -0.2228 -0.3512 1.6246 0.9006 -0.1200 0.0777 -0.4105 +1305031464.2693 -0.2198 -0.3526 1.6280 0.9006 -0.1172 0.0736 -0.4120 +1305031464.2794 -0.2171 -0.3545 1.6312 0.9016 -0.1131 0.0683 -0.4119 +1305031464.2893 -0.2140 -0.3562 1.6346 0.9022 -0.1097 0.0643 -0.4122 +1305031464.2993 -0.2106 -0.3579 1.6378 0.9027 -0.1057 0.0606 -0.4126 +1305031464.3093 -0.2075 -0.3595 1.6411 0.9029 -0.1029 0.0576 -0.4134 +1305031464.3193 -0.2041 -0.3610 1.6443 0.9029 -0.1002 0.0549 -0.4143 +1305031464.3293 -0.2003 -0.3627 1.6477 0.9034 -0.0972 0.0524 -0.4143 +1305031464.3393 -0.1965 -0.3641 1.6510 0.9030 -0.0945 0.0496 -0.4161 +1305031464.3493 -0.1927 -0.3660 1.6545 0.9030 -0.0922 0.0477 -0.4170 +1305031464.3593 -0.1888 -0.3674 1.6579 0.9025 -0.0899 0.0460 -0.4187 +1305031464.3693 -0.1847 -0.3690 1.6614 0.9020 -0.0870 0.0445 -0.4205 +1305031464.3793 -0.1807 -0.3706 1.6650 0.9017 -0.0841 0.0438 -0.4218 +1305031464.3893 -0.1764 -0.3723 1.6685 0.9013 -0.0817 0.0437 -0.4233 +1305031464.3993 -0.1723 -0.3741 1.6721 0.9014 -0.0789 0.0443 -0.4234 +1305031464.4093 -0.1679 -0.3758 1.6757 0.9014 -0.0758 0.0447 -0.4239 +1305031464.4193 -0.1636 -0.3776 1.6795 0.9017 -0.0729 0.0457 -0.4238 +1305031464.4293 -0.1591 -0.3794 1.6833 0.9016 -0.0698 0.0463 -0.4244 +1305031464.4393 -0.1546 -0.3810 1.6872 0.9014 -0.0668 0.0465 -0.4252 +1305031464.4494 -0.1501 -0.3827 1.6913 0.9011 -0.0637 0.0459 -0.4264 +1305031464.4593 -0.1456 -0.3844 1.6953 0.9006 -0.0613 0.0457 -0.4278 +1305031464.4693 -0.1410 -0.3861 1.6996 0.9005 -0.0591 0.0445 -0.4285 +1305031464.4792 -0.1363 -0.3878 1.7038 0.9006 -0.0575 0.0446 -0.4286 +1305031464.4893 -0.1318 -0.3896 1.7083 0.8992 -0.0556 0.0451 -0.4316 +1305031464.4998 -0.1272 -0.3913 1.7128 0.8992 -0.0540 0.0455 -0.4318 +1305031464.5095 -0.1228 -0.3934 1.7174 0.8997 -0.0518 0.0461 -0.4311 +1305031464.5194 -0.1186 -0.3953 1.7219 0.8997 -0.0489 0.0466 -0.4313 +1305031464.5294 -0.1142 -0.3973 1.7264 0.8998 -0.0453 0.0474 -0.4313 +1305031464.5395 -0.1099 -0.3996 1.7310 0.9007 -0.0415 0.0479 -0.4297 +1305031464.5494 -0.1059 -0.4017 1.7357 0.9013 -0.0379 0.0486 -0.4288 +1305031464.5593 -0.1018 -0.4037 1.7406 0.9019 -0.0343 0.0499 -0.4277 +1305031464.5693 -0.0978 -0.4059 1.7457 0.9017 -0.0316 0.0519 -0.4282 +1305031464.5793 -0.0937 -0.4080 1.7509 0.9007 -0.0297 0.0542 -0.4299 +1305031464.5893 -0.0895 -0.4102 1.7561 0.8991 -0.0284 0.0576 -0.4330 +1305031464.5993 -0.0855 -0.4123 1.7613 0.8978 -0.0269 0.0608 -0.4353 +1305031464.6093 -0.0814 -0.4143 1.7666 0.8960 -0.0263 0.0645 -0.4385 +1305031464.6195 -0.0774 -0.4163 1.7717 0.8945 -0.0255 0.0682 -0.4411 +1305031464.6293 -0.0735 -0.4179 1.7767 0.8927 -0.0241 0.0722 -0.4443 +1305031464.6393 -0.0697 -0.4196 1.7818 0.8917 -0.0228 0.0758 -0.4456 +1305031464.6493 -0.0656 -0.4211 1.7866 0.8895 -0.0194 0.0803 -0.4493 +1305031464.6593 -0.0617 -0.4223 1.7916 0.8875 -0.0162 0.0849 -0.4526 +1305031464.6693 -0.0579 -0.4235 1.7964 0.8861 -0.0131 0.0889 -0.4548 +1305031464.6794 -0.0542 -0.4241 1.8012 0.8832 -0.0094 0.0930 -0.4596 +1305031464.6893 -0.0503 -0.4247 1.8059 0.8804 -0.0059 0.0965 -0.4642 +1305031464.6993 -0.0465 -0.4253 1.8107 0.8779 -0.0020 0.1000 -0.4683 +1305031464.7093 -0.0430 -0.4254 1.8151 0.8753 0.0020 0.1020 -0.4728 +1305031464.7193 -0.0394 -0.4254 1.8195 0.8725 0.0064 0.1041 -0.4774 +1305031464.7293 -0.0360 -0.4253 1.8234 0.8703 0.0112 0.1057 -0.4810 +1305031464.7393 -0.0326 -0.4250 1.8274 0.8682 0.0161 0.1070 -0.4843 +1305031464.7493 -0.0292 -0.4244 1.8309 0.8662 0.0221 0.1081 -0.4873 +1305031464.7593 -0.0256 -0.4240 1.8342 0.8650 0.0283 0.1086 -0.4891 +1305031464.7693 -0.0222 -0.4233 1.8374 0.8641 0.0341 0.1094 -0.4902 +1305031464.7793 -0.0189 -0.4223 1.8403 0.8631 0.0400 0.1093 -0.4915 +1305031464.7893 -0.0157 -0.4212 1.8431 0.8622 0.0455 0.1090 -0.4926 +1305031464.7993 -0.0123 -0.4201 1.8459 0.8609 0.0511 0.1072 -0.4947 +1305031464.8093 -0.0090 -0.4187 1.8484 0.8596 0.0567 0.1048 -0.4969 +1305031464.8193 -0.0060 -0.4170 1.8508 -0.8578 -0.0625 -0.1017 0.5000 +1305031464.8293 -0.0028 -0.4154 1.8529 -0.8567 -0.0681 -0.0981 0.5018 +1305031464.8393 0.0004 -0.4134 1.8550 -0.8559 -0.0745 -0.0948 0.5028 +1305031464.8493 0.0034 -0.4114 1.8569 -0.8555 -0.0811 -0.0915 0.5032 +1305031464.8593 0.0064 -0.4090 1.8586 -0.8550 -0.0882 -0.0886 0.5034 +1305031464.8693 0.0097 -0.4067 1.8603 -0.8551 -0.0959 -0.0864 0.5022 +1305031464.8795 0.0130 -0.4040 1.8616 -0.8554 -0.1037 -0.0841 0.5005 +1305031464.8893 0.0162 -0.4009 1.8630 0.8554 0.1119 0.0824 -0.4990 +1305031464.8993 0.0195 -0.3980 1.8642 0.8556 0.1196 0.0810 -0.4971 +1305031464.9093 0.0229 -0.3949 1.8651 0.8552 0.1267 0.0797 -0.4962 +1305031464.9193 0.0264 -0.3917 1.8661 0.8545 0.1334 0.0792 -0.4957 +1305031464.9293 0.0298 -0.3884 1.8668 0.8533 0.1389 0.0783 -0.4964 +1305031464.9393 0.0332 -0.3847 1.8675 0.8520 0.1441 0.0784 -0.4971 +1305031464.9493 0.0370 -0.3812 1.8679 0.8508 0.1489 0.0785 -0.4978 +1305031464.9593 0.0409 -0.3780 1.8680 0.8494 0.1546 0.0789 -0.4983 +1305031464.9693 0.0448 -0.3742 1.8679 0.8475 0.1594 0.0795 -0.5000 +1305031464.9793 0.0486 -0.3705 1.8673 -0.8456 -0.1645 -0.0809 0.5014 +1305031464.9893 0.0523 -0.3668 1.8666 -0.8440 -0.1696 -0.0825 0.5021 +1305031464.9993 0.0562 -0.3628 1.8655 -0.8418 -0.1753 -0.0845 0.5035 +1305031465.0093 0.0601 -0.3590 1.8640 -0.8402 -0.1815 -0.0867 0.5036 +1305031465.0193 0.0639 -0.3555 1.8624 -0.8383 -0.1872 -0.0888 0.5044 +1305031465.0293 0.0677 -0.3518 1.8604 -0.8361 -0.1934 -0.0901 0.5054 +1305031465.0393 0.0716 -0.3481 1.8582 -0.8337 -0.1999 -0.0902 0.5068 +1305031465.0493 0.0754 -0.3443 1.8555 -0.8310 -0.2063 -0.0900 0.5087 +1305031465.0593 0.0791 -0.3407 1.8523 -0.8292 -0.2124 -0.0887 0.5093 +1305031465.0693 0.0830 -0.3370 1.8488 -0.8284 -0.2190 -0.0875 0.5080 +1305031465.0793 0.0869 -0.3336 1.8448 -0.8288 -0.2259 -0.0862 0.5045 +1305031465.0893 0.0911 -0.3298 1.8404 -0.8293 -0.2329 -0.0853 0.5008 +1305031465.0993 0.0953 -0.3263 1.8356 0.8307 0.2399 0.0846 -0.4952 +1305031465.1093 0.0998 -0.3227 1.8305 0.8323 0.2465 0.0839 -0.4894 +1305031465.1193 0.1043 -0.3191 1.8254 0.8336 0.2523 0.0826 -0.4843 +1305031465.1293 0.1090 -0.3155 1.8201 0.8354 0.2572 0.0817 -0.4787 +1305031465.1393 0.1136 -0.3121 1.8146 0.8373 0.2613 0.0799 -0.4736 +1305031465.1493 0.1185 -0.3085 1.8092 0.8386 0.2651 0.0781 -0.4695 +1305031465.1593 0.1236 -0.3054 1.8037 0.8402 0.2684 0.0763 -0.4649 +1305031465.1693 0.1287 -0.3021 1.7983 0.8410 0.2721 0.0740 -0.4618 +1305031465.1793 0.1338 -0.2988 1.7927 0.8419 0.2753 0.0721 -0.4585 +1305031465.1893 0.1392 -0.2954 1.7872 0.8425 0.2786 0.0701 -0.4557 +1305031465.1993 0.1447 -0.2922 1.7818 0.8433 0.2813 0.0684 -0.4529 +1305031465.2093 0.1502 -0.2890 1.7763 0.8443 0.2841 0.0670 -0.4495 +1305031465.2193 0.1558 -0.2858 1.7708 0.8453 0.2871 0.0652 -0.4460 +1305031465.2293 0.1618 -0.2828 1.7654 0.8469 0.2894 0.0636 -0.4416 +1305031465.2393 0.1678 -0.2800 1.7601 0.8483 0.2912 0.0618 -0.4379 +1305031465.2493 0.1740 -0.2769 1.7549 0.8491 0.2922 0.0586 -0.4361 +1305031465.2593 0.1804 -0.2741 1.7500 0.8507 0.2923 0.0557 -0.4334 +1305031465.2693 0.1868 -0.2713 1.7450 0.8514 0.2915 0.0513 -0.4330 +1305031465.2793 0.1934 -0.2686 1.7403 0.8528 0.2901 0.0471 -0.4317 +1305031465.2893 0.2002 -0.2659 1.7354 0.8543 0.2884 0.0423 -0.4303 +1305031465.2993 0.2070 -0.2633 1.7307 0.8566 0.2864 0.0376 -0.4276 +1305031465.3093 0.2137 -0.2605 1.7261 0.8582 0.2853 0.0323 -0.4254 +1305031465.3193 0.2207 -0.2581 1.7215 0.8601 0.2839 0.0265 -0.4230 +1305031465.3293 0.2275 -0.2561 1.7174 0.8625 0.2829 0.0203 -0.4192 +1305031465.3393 0.2345 -0.2537 1.7133 0.8639 0.2815 0.0144 -0.4175 +1305031465.3493 0.2416 -0.2514 1.7093 0.8645 0.2802 0.0075 -0.4172 +1305031465.3593 0.2487 -0.2492 1.7054 0.8651 0.2791 0.0006 -0.4168 +1305031465.3693 0.2560 -0.2470 1.7017 0.8650 0.2783 -0.0066 -0.4174 +1305031465.3793 0.2633 -0.2453 1.6983 0.8658 0.2772 -0.0136 -0.4164 +1305031465.3893 0.2707 -0.2434 1.6948 0.8655 0.2764 -0.0198 -0.4172 +1305031465.3993 0.2782 -0.2417 1.6917 0.8659 0.2750 -0.0258 -0.4170 +1305031465.4093 0.2857 -0.2402 1.6887 0.8663 0.2740 -0.0315 -0.4166 +1305031465.4193 0.2934 -0.2386 1.6857 0.8665 0.2721 -0.0367 -0.4168 +1305031465.4293 0.3009 -0.2374 1.6828 0.8669 0.2703 -0.0417 -0.4168 +1305031465.4393 0.3087 -0.2363 1.6799 0.8672 0.2678 -0.0471 -0.4172 +1305031465.4493 0.3163 -0.2351 1.6771 0.8674 0.2653 -0.0525 -0.4178 +1305031465.4593 0.3242 -0.2342 1.6743 0.8682 0.2630 -0.0576 -0.4168 +1305031465.4699 0.3318 -0.2334 1.6716 0.8691 0.2614 -0.0623 -0.4154 +1305031465.4793 0.3395 -0.2325 1.6689 0.8697 0.2599 -0.0666 -0.4142 +1305031465.4893 0.3470 -0.2319 1.6664 0.8705 0.2592 -0.0700 -0.4125 +1305031465.4993 0.3546 -0.2315 1.6639 0.8710 0.2594 -0.0735 -0.4107 +1305031465.5093 0.3621 -0.2310 1.6616 0.8707 0.2598 -0.0769 -0.4105 +1305031465.5193 0.3701 -0.2309 1.6594 0.8706 0.2600 -0.0800 -0.4101 +1305031465.5293 0.3779 -0.2307 1.6574 0.8695 0.2599 -0.0843 -0.4115 +1305031465.5393 0.3857 -0.2306 1.6553 0.8683 0.2597 -0.0884 -0.4132 +1305031465.5493 0.3937 -0.2305 1.6534 0.8672 0.2590 -0.0924 -0.4151 +1305031465.5594 0.4019 -0.2306 1.6512 0.8668 0.2575 -0.0960 -0.4161 +1305031465.5693 0.4100 -0.2307 1.6492 0.8667 0.2553 -0.0989 -0.4169 +1305031465.5794 0.4181 -0.2308 1.6471 0.8665 0.2536 -0.1020 -0.4177 +1305031465.5893 0.4263 -0.2311 1.6449 0.8665 0.2514 -0.1048 -0.4184 +1305031465.5993 0.4347 -0.2313 1.6427 0.8664 0.2494 -0.1072 -0.4191 +1305031465.6093 0.4430 -0.2316 1.6403 0.8658 0.2473 -0.1102 -0.4209 +1305031465.6193 0.4515 -0.2324 1.6381 0.8657 0.2455 -0.1136 -0.4212 +1305031465.6293 0.4598 -0.2333 1.6357 0.8657 0.2444 -0.1174 -0.4208 +1305031465.6393 0.4681 -0.2341 1.6332 0.8651 0.2432 -0.1223 -0.4214 +1305031465.6493 0.4766 -0.2348 1.6308 0.8644 0.2422 -0.1269 -0.4220 +1305031465.6593 0.4850 -0.2356 1.6282 0.8635 0.2410 -0.1313 -0.4231 +1305031465.6693 0.4935 -0.2363 1.6256 0.8627 0.2402 -0.1356 -0.4239 +1305031465.6793 0.5019 -0.2370 1.6230 0.8620 0.2387 -0.1387 -0.4251 +1305031465.6893 0.5105 -0.2379 1.6202 0.8615 0.2374 -0.1415 -0.4260 +1305031465.6993 0.5191 -0.2386 1.6173 0.8608 0.2351 -0.1441 -0.4278 +1305031465.7093 0.5279 -0.2395 1.6145 0.8602 0.2329 -0.1470 -0.4292 +1305031465.7193 0.5366 -0.2403 1.6115 0.8594 0.2305 -0.1498 -0.4312 +1305031465.7293 0.5454 -0.2412 1.6083 0.8587 0.2285 -0.1530 -0.4325 +1305031465.7393 0.5539 -0.2422 1.6051 0.8578 0.2262 -0.1565 -0.4342 +1305031465.7493 0.5628 -0.2430 1.6018 0.8574 0.2236 -0.1597 -0.4352 +1305031465.7593 0.5715 -0.2438 1.5984 0.8569 0.2224 -0.1624 -0.4357 +1305031465.7693 0.5800 -0.2444 1.5948 0.8560 0.2208 -0.1656 -0.4372 +1305031465.7792 0.5887 -0.2452 1.5914 0.8554 0.2196 -0.1677 -0.4382 +1305031465.7893 0.5974 -0.2460 1.5876 0.8546 0.2179 -0.1699 -0.4398 +1305031465.7993 0.6062 -0.2471 1.5840 0.8539 0.2169 -0.1718 -0.4407 +1305031465.8093 0.6151 -0.2479 1.5803 0.8526 0.2158 -0.1742 -0.4430 +1305031465.8193 0.6236 -0.2488 1.5766 0.8508 0.2143 -0.1775 -0.4457 +1305031465.8293 0.6326 -0.2496 1.5729 0.8491 0.2135 -0.1798 -0.4484 +1305031465.8393 0.6412 -0.2504 1.5690 0.8475 0.2115 -0.1831 -0.4511 +1305031465.8493 0.6499 -0.2512 1.5650 0.8462 0.2096 -0.1848 -0.4537 +1305031465.8592 0.6586 -0.2521 1.5608 0.8455 0.2078 -0.1861 -0.4553 +1305031465.8693 0.6672 -0.2530 1.5565 0.8456 0.2062 -0.1863 -0.4558 +1305031465.8793 0.6758 -0.2539 1.5523 0.8461 0.2049 -0.1857 -0.4557 +1305031465.8893 0.6843 -0.2549 1.5480 0.8461 0.2034 -0.1848 -0.4567 +1305031465.8993 0.6930 -0.2558 1.5437 0.8458 0.2023 -0.1839 -0.4582 +1305031465.9093 0.7016 -0.2567 1.5394 0.8452 0.2009 -0.1825 -0.4605 +1305031465.9192 0.7100 -0.2576 1.5352 0.8439 0.1997 -0.1821 -0.4635 +1305031465.9292 0.7185 -0.2586 1.5311 0.8427 0.1983 -0.1813 -0.4666 +1305031465.9393 0.7268 -0.2595 1.5269 0.8409 0.1972 -0.1806 -0.4705 +1305031465.9493 0.7350 -0.2605 1.5227 0.8392 0.1964 -0.1799 -0.4741 +1305031465.9593 0.7429 -0.2615 1.5186 0.8380 0.1952 -0.1788 -0.4772 +1305031465.9701 0.7509 -0.2626 1.5144 0.8371 0.1951 -0.1772 -0.4794 +1305031465.9793 0.7588 -0.2637 1.5100 0.8358 0.1952 -0.1761 -0.4820 +1305031465.9893 0.7664 -0.2650 1.5057 0.8351 0.1960 -0.1752 -0.4833 +1305031465.9993 0.7740 -0.2664 1.5014 0.8339 0.1964 -0.1753 -0.4852 +1305031466.0093 0.7819 -0.2678 1.4973 0.8328 0.1968 -0.1751 -0.4869 +1305031466.0193 0.7891 -0.2689 1.4928 0.8312 0.1957 -0.1763 -0.4896 +1305031466.0293 0.7966 -0.2706 1.4887 0.8316 0.1959 -0.1761 -0.4890 +1305031466.0393 0.8039 -0.2720 1.4845 0.8317 0.1950 -0.1764 -0.4889 +1305031466.0493 0.8110 -0.2738 1.4802 0.8331 0.1949 -0.1765 -0.4867 +1305031466.0593 0.8181 -0.2756 1.4763 0.8340 0.1944 -0.1760 -0.4855 +1305031466.0692 0.8250 -0.2773 1.4723 0.8340 0.1946 -0.1769 -0.4851 +1305031466.0793 0.8320 -0.2794 1.4686 0.8346 0.1954 -0.1771 -0.4836 +1305031466.0893 0.8387 -0.2814 1.4651 0.8343 0.1961 -0.1787 -0.4834 +1305031466.0993 0.8454 -0.2839 1.4617 0.8351 0.1974 -0.1795 -0.4810 +1305031466.1093 0.8523 -0.2863 1.4586 0.8357 0.1984 -0.1804 -0.4793 +1305031466.1193 0.8592 -0.2889 1.4557 0.8364 0.1993 -0.1816 -0.4772 +1305031466.1293 0.8659 -0.2917 1.4531 0.8372 0.1997 -0.1824 -0.4754 +1305031466.1393 0.8725 -0.2943 1.4506 0.8375 0.1997 -0.1839 -0.4742 +1305031466.1493 0.8790 -0.2972 1.4483 0.8380 0.2006 -0.1859 -0.4722 +1305031466.1593 0.8854 -0.2998 1.4461 0.8379 0.2010 -0.1888 -0.4710 +1305031466.1693 0.8919 -0.3027 1.4442 0.8385 0.2018 -0.1911 -0.4687 +1305031466.1792 0.8982 -0.3052 1.4425 0.8385 0.2030 -0.1941 -0.4669 +1305031466.1893 0.9045 -0.3082 1.4412 0.8396 0.2050 -0.1960 -0.4633 +1305031466.1993 0.9110 -0.3110 1.4400 0.8405 0.2074 -0.1976 -0.4599 +1305031466.2093 0.9173 -0.3139 1.4389 0.8416 0.2101 -0.1985 -0.4562 +1305031466.2193 0.9236 -0.3167 1.4381 0.8422 0.2129 -0.1999 -0.4533 +1305031466.2293 0.9300 -0.3195 1.4378 0.8427 0.2157 -0.1999 -0.4511 +1305031466.2393 0.9365 -0.3222 1.4377 0.8424 0.2176 -0.1998 -0.4506 +1305031466.2493 0.9431 -0.3251 1.4381 0.8419 0.2205 -0.1990 -0.4506 +1305031466.2593 0.9494 -0.3275 1.4383 0.8401 0.2222 -0.1981 -0.4534 +1305031466.2692 0.9560 -0.3301 1.4389 0.8395 0.2246 -0.1958 -0.4543 +1305031466.2793 0.9628 -0.3325 1.4395 0.8391 0.2271 -0.1927 -0.4553 +1305031466.2893 0.9693 -0.3345 1.4403 0.8382 0.2290 -0.1899 -0.4572 +1305031466.2993 0.9759 -0.3368 1.4410 0.8385 0.2305 -0.1859 -0.4575 +1305031466.3093 0.9824 -0.3386 1.4417 0.8380 0.2320 -0.1827 -0.4589 +1305031466.3193 0.9896 -0.3404 1.4429 0.8391 0.2345 -0.1769 -0.4580 +1305031466.3293 0.9956 -0.3422 1.4431 0.8389 0.2334 -0.1752 -0.4593 +1305031466.3393 1.0020 -0.3436 1.4438 0.8395 0.2343 -0.1723 -0.4590 +1305031466.3493 1.0085 -0.3452 1.4445 0.8406 0.2348 -0.1692 -0.4579 +1305031466.3593 1.0151 -0.3467 1.4453 0.8415 0.2363 -0.1668 -0.4564 +1305031466.3693 1.0214 -0.3481 1.4461 0.8410 0.2371 -0.1652 -0.4573 +1305031466.3793 1.0280 -0.3493 1.4471 0.8401 0.2388 -0.1647 -0.4583 +1305031466.3893 1.0345 -0.3509 1.4482 0.8392 0.2396 -0.1643 -0.4597 +1305031466.3993 1.0409 -0.3523 1.4492 0.8375 0.2410 -0.1651 -0.4618 +1305031466.4093 1.0475 -0.3534 1.4502 0.8363 0.2421 -0.1657 -0.4632 +1305031466.4193 1.0540 -0.3547 1.4508 0.8353 0.2437 -0.1669 -0.4637 +1305031466.4293 1.0604 -0.3556 1.4515 0.8344 0.2455 -0.1680 -0.4640 +1305031466.4393 1.0669 -0.3563 1.4518 0.8337 0.2472 -0.1686 -0.4640 +1305031466.4493 1.0733 -0.3571 1.4519 0.8339 0.2493 -0.1697 -0.4622 +1305031466.4592 1.0799 -0.3576 1.4519 0.8341 0.2512 -0.1706 -0.4606 +1305031466.4692 1.0863 -0.3581 1.4519 0.8342 0.2524 -0.1719 -0.4592 +1305031466.4794 1.0929 -0.3583 1.4517 0.8347 0.2530 -0.1728 -0.4576 +1305031466.4893 1.0997 -0.3584 1.4516 0.8358 0.2532 -0.1725 -0.4556 +1305031466.4993 1.1065 -0.3582 1.4512 0.8357 0.2527 -0.1734 -0.4558 +1305031466.5093 1.1132 -0.3580 1.4507 0.8359 0.2524 -0.1728 -0.4557 +1305031466.5193 1.1203 -0.3578 1.4504 0.8369 0.2532 -0.1712 -0.4540 +1305031466.5293 1.1270 -0.3572 1.4497 0.8359 0.2525 -0.1709 -0.4565 +1305031466.5393 1.1339 -0.3566 1.4490 0.8360 0.2527 -0.1701 -0.4564 +1305031466.5495 1.1407 -0.3559 1.4482 0.8365 0.2528 -0.1690 -0.4559 +1305031466.5593 1.1476 -0.3550 1.4474 0.8374 0.2539 -0.1682 -0.4538 +1305031466.5693 1.1544 -0.3539 1.4464 0.8381 0.2549 -0.1676 -0.4522 +1305031466.5792 1.1612 -0.3526 1.4454 0.8389 0.2568 -0.1677 -0.4496 +1305031466.5893 1.1681 -0.3514 1.4444 0.8403 0.2577 -0.1665 -0.4469 +1305031466.5992 1.1751 -0.3503 1.4436 0.8418 0.2595 -0.1651 -0.4436 +1305031466.6093 1.1820 -0.3491 1.4427 0.8423 0.2606 -0.1639 -0.4424 +1305031466.6193 1.1890 -0.3478 1.4422 0.8420 0.2612 -0.1632 -0.4429 +1305031466.6293 1.1958 -0.3465 1.4414 0.8407 0.2617 -0.1625 -0.4454 +1305031466.6392 1.2028 -0.3452 1.4412 0.8392 0.2626 -0.1615 -0.4479 +1305031466.6493 1.2098 -0.3436 1.4407 0.8378 0.2642 -0.1609 -0.4499 +1305031466.6592 1.2163 -0.3423 1.4401 0.8363 0.2654 -0.1604 -0.4521 +1305031466.6692 1.2229 -0.3410 1.4395 0.8354 0.2674 -0.1599 -0.4528 +1305031466.6794 1.2295 -0.3396 1.4386 0.8349 0.2701 -0.1597 -0.4523 +1305031466.6893 1.2360 -0.3382 1.4379 0.8348 0.2734 -0.1592 -0.4506 +1305031466.6993 1.2426 -0.3365 1.4368 0.8347 0.2764 -0.1581 -0.4494 +1305031466.7093 1.2488 -0.3352 1.4362 0.8349 0.2796 -0.1580 -0.4469 +1305031466.7193 1.2554 -0.3340 1.4356 0.8357 0.2826 -0.1564 -0.4442 +1305031466.7293 1.2616 -0.3322 1.4349 0.8342 0.2851 -0.1569 -0.4453 +1305031466.7392 1.2680 -0.3309 1.4345 0.8333 0.2874 -0.1554 -0.4459 +1305031466.7493 1.2744 -0.3296 1.4344 0.8318 0.2892 -0.1550 -0.4477 +1305031466.7593 1.2807 -0.3281 1.4342 0.8297 0.2905 -0.1549 -0.4507 +1305031466.7693 1.2870 -0.3268 1.4340 0.8280 0.2927 -0.1547 -0.4526 +1305031466.7793 1.2930 -0.3253 1.4338 0.8263 0.2942 -0.1556 -0.4544 +1305031466.7893 1.2991 -0.3238 1.4334 0.8252 0.2962 -0.1558 -0.4550 +1305031466.7993 1.3051 -0.3225 1.4331 0.8250 0.2982 -0.1565 -0.4539 +1305031466.8092 1.3108 -0.3210 1.4327 0.8251 0.2996 -0.1573 -0.4524 +1305031466.8196 1.3166 -0.3194 1.4323 0.8253 0.3012 -0.1582 -0.4508 +1305031466.8293 1.3223 -0.3180 1.4320 0.8258 0.3022 -0.1592 -0.4489 +1305031466.8393 1.3280 -0.3168 1.4319 0.8259 0.3028 -0.1609 -0.4476 +1305031466.8493 1.3335 -0.3155 1.4319 0.8256 0.3029 -0.1630 -0.4473 +1305031466.8593 1.3390 -0.3142 1.4320 0.8247 0.3037 -0.1656 -0.4475 +1305031466.8693 1.3443 -0.3129 1.4322 0.8230 0.3050 -0.1689 -0.4484 +1305031466.8793 1.3496 -0.3116 1.4324 0.8217 0.3072 -0.1722 -0.4482 +1305031466.8893 1.3549 -0.3102 1.4327 0.8201 0.3095 -0.1759 -0.4480 +1305031466.8993 1.3603 -0.3088 1.4329 0.8194 0.3121 -0.1793 -0.4462 +1305031466.9093 1.3654 -0.3073 1.4330 0.8179 0.3146 -0.1831 -0.4456 +1305031466.9193 1.3706 -0.3058 1.4332 0.8168 0.3165 -0.1869 -0.4448 +1305031466.9292 1.3756 -0.3043 1.4334 0.8161 0.3184 -0.1901 -0.4432 +1305031466.9393 1.3809 -0.3027 1.4338 0.8150 0.3195 -0.1931 -0.4432 +1305031466.9493 1.3859 -0.3011 1.4341 0.8137 0.3202 -0.1965 -0.4435 +1305031466.9593 1.3908 -0.2994 1.4343 0.8124 0.3211 -0.1992 -0.4442 +1305031466.9693 1.3960 -0.2977 1.4347 0.8119 0.3226 -0.2004 -0.4434 +1305031466.9792 1.4014 -0.2962 1.4352 0.8116 0.3240 -0.2005 -0.4429 +1305031466.9893 1.4066 -0.2948 1.4356 0.8118 0.3257 -0.2002 -0.4415 +1305031466.9994 1.4114 -0.2929 1.4362 0.8108 0.3276 -0.2009 -0.4415 +1305031467.0092 1.4164 -0.2912 1.4366 0.8101 0.3292 -0.2014 -0.4413 +1305031467.0193 1.4216 -0.2896 1.4368 0.8093 0.3310 -0.2021 -0.4411 +1305031467.0292 1.4268 -0.2879 1.4371 0.8091 0.3318 -0.2030 -0.4405 +1305031467.0392 1.4319 -0.2862 1.4372 0.8086 0.3335 -0.2028 -0.4403 +1305031467.0493 1.4367 -0.2844 1.4374 0.8081 0.3339 -0.2035 -0.4405 +1305031467.0593 1.4418 -0.2825 1.4375 0.8080 0.3353 -0.2033 -0.4398 +1305031467.0693 1.4463 -0.2806 1.4374 0.8070 0.3364 -0.2040 -0.4403 +1305031467.0792 1.4511 -0.2789 1.4375 0.8070 0.3384 -0.2028 -0.4394 +1305031467.0893 1.4558 -0.2772 1.4374 0.8064 0.3409 -0.2024 -0.4388 +1305031467.0992 1.4606 -0.2759 1.4373 0.8059 0.3438 -0.2012 -0.4380 +1305031467.1092 1.4642 -0.2738 1.4370 0.8025 0.3455 -0.2041 -0.4416 +1305031467.1193 1.4694 -0.2724 1.4373 0.8020 0.3502 -0.2019 -0.4398 +1305031467.1293 1.4740 -0.2710 1.4374 0.8009 0.3524 -0.2011 -0.4403 +1305031467.1393 1.4781 -0.2692 1.4372 0.7989 0.3549 -0.2019 -0.4416 +1305031467.1493 1.4826 -0.2676 1.4373 0.7977 0.3570 -0.2021 -0.4420 +1305031467.1592 1.4870 -0.2663 1.4371 0.7970 0.3578 -0.2029 -0.4423 +1305031467.1693 1.4914 -0.2647 1.4373 0.7967 0.3606 -0.2021 -0.4409 +1305031467.1794 1.4954 -0.2629 1.4371 0.7946 0.3623 -0.2045 -0.4421 +1305031467.1893 1.4998 -0.2616 1.4374 0.7942 0.3649 -0.2045 -0.4407 +1305031467.1992 1.5038 -0.2600 1.4373 0.7921 0.3669 -0.2065 -0.4419 +1305031467.2093 1.5083 -0.2586 1.4375 0.7915 0.3698 -0.2071 -0.4403 +1305031467.2193 1.5126 -0.2573 1.4374 0.7907 0.3721 -0.2080 -0.4395 +1305031467.2293 1.5167 -0.2560 1.4374 0.7895 0.3735 -0.2096 -0.4396 +1305031467.2393 1.5212 -0.2548 1.4373 0.7891 0.3751 -0.2101 -0.4387 +1305031467.2493 1.5252 -0.2530 1.4377 0.7867 0.3770 -0.2117 -0.4407 +1305031467.2592 1.5299 -0.2518 1.4376 0.7860 0.3788 -0.2118 -0.4403 +1305031467.2693 1.5342 -0.2505 1.4378 0.7845 0.3813 -0.2123 -0.4406 +1305031467.2792 1.5383 -0.2490 1.4378 0.7825 0.3838 -0.2135 -0.4413 +1305031467.2892 1.5429 -0.2480 1.4379 0.7817 0.3859 -0.2141 -0.4407 +1305031467.2992 1.5474 -0.2467 1.4381 0.7802 0.3881 -0.2147 -0.4411 +1305031467.3092 1.5517 -0.2454 1.4380 0.7788 0.3902 -0.2160 -0.4412 +1305031467.3192 1.5564 -0.2441 1.4384 0.7781 0.3921 -0.2160 -0.4407 +1305031467.3292 1.5605 -0.2428 1.4381 0.7768 0.3934 -0.2185 -0.4405 +1305031467.3393 1.5651 -0.2414 1.4382 0.7765 0.3942 -0.2198 -0.4397 +1305031467.3493 1.5693 -0.2399 1.4382 0.7758 0.3961 -0.2214 -0.4384 +1305031467.3592 1.5739 -0.2388 1.4382 0.7760 0.3981 -0.2225 -0.4356 +1305031467.3693 1.5785 -0.2375 1.4382 0.7762 0.4004 -0.2230 -0.4330 +1305031467.3793 1.5829 -0.2363 1.4379 0.7755 0.4028 -0.2241 -0.4314 +1305031467.3893 1.5871 -0.2347 1.4381 0.7734 0.4056 -0.2267 -0.4311 +1305031467.3993 1.5920 -0.2339 1.4384 0.7740 0.4069 -0.2268 -0.4289 +1305031467.4092 1.5969 -0.2328 1.4384 0.7736 0.4092 -0.2267 -0.4274 +1305031467.4193 1.6018 -0.2313 1.4387 0.7727 0.4100 -0.2280 -0.4277 +1305031467.4292 1.6063 -0.2300 1.4390 0.7712 0.4108 -0.2302 -0.4284 +1305031467.4392 1.6113 -0.2289 1.4394 0.7708 0.4119 -0.2318 -0.4271 +1305031467.4493 1.6151 -0.2275 1.4391 0.7685 0.4127 -0.2356 -0.4284 +1305031467.4592 1.6200 -0.2264 1.4394 0.7679 0.4147 -0.2370 -0.4269 +1305031467.5092 1.6429 -0.2189 1.4393 0.7648 0.4267 -0.2396 -0.4191 +1305031467.5193 1.6475 -0.2175 1.4394 0.7644 0.4288 -0.2394 -0.4177 +1305031467.5293 1.6519 -0.2157 1.4396 0.7638 0.4301 -0.2393 -0.4175 +1305031467.5392 1.6564 -0.2137 1.4403 0.7634 0.4317 -0.2380 -0.4173 +1305031467.5493 1.6606 -0.2118 1.4406 0.7632 0.4317 -0.2382 -0.4177 +1305031467.5592 1.6647 -0.2096 1.4409 0.7630 0.4318 -0.2384 -0.4176 +1305031467.5692 1.6686 -0.2072 1.4414 0.7626 0.4316 -0.2393 -0.4182 +1305031467.5794 1.6724 -0.2047 1.4418 0.7625 0.4320 -0.2399 -0.4175 +1305031467.5892 1.6762 -0.2022 1.4423 0.7627 0.4318 -0.2406 -0.4171 +1305031467.5993 1.6801 -0.1999 1.4429 0.7634 0.4323 -0.2406 -0.4153 +1305031467.6094 1.6834 -0.1971 1.4434 0.7630 0.4325 -0.2424 -0.4147 +1305031467.6192 1.6866 -0.1941 1.4440 0.7619 0.4321 -0.2452 -0.4155 +1305031467.6292 1.6898 -0.1913 1.4448 0.7613 0.4316 -0.2470 -0.4162 +1305031467.6392 1.6915 -0.1882 1.4449 0.7584 0.4296 -0.2536 -0.4194 +1305031467.6493 1.6945 -0.1851 1.4456 0.7579 0.4291 -0.2555 -0.4197 +1305031467.6593 1.6966 -0.1815 1.4461 0.7562 0.4280 -0.2579 -0.4224 +1305031467.6793 1.7015 -0.1745 1.4473 0.7548 0.4295 -0.2603 -0.4219 +1305031467.6893 1.7035 -0.1711 1.4476 0.7542 0.4324 -0.2600 -0.4202 +1305031467.6992 1.7051 -0.1673 1.4479 0.7524 0.4334 -0.2612 -0.4218 +1305031467.7093 1.7069 -0.1636 1.4483 0.7513 0.4346 -0.2609 -0.4227 +1305031467.7193 1.7085 -0.1595 1.4487 0.7495 0.4361 -0.2616 -0.4239 +1305031467.7293 1.7099 -0.1557 1.4491 0.7485 0.4362 -0.2618 -0.4253 +1305031467.7392 1.7114 -0.1514 1.4495 0.7482 0.4373 -0.2611 -0.4252 +1305031467.7493 1.7122 -0.1470 1.4499 0.7456 0.4367 -0.2635 -0.4289 +1305031467.7592 1.7131 -0.1426 1.4499 0.7446 0.4379 -0.2640 -0.4291 +1305031467.7693 1.7138 -0.1384 1.4500 0.7439 0.4391 -0.2645 -0.4288 +1305031467.7793 1.7143 -0.1337 1.4500 0.7423 0.4400 -0.2660 -0.4297 +1305031467.7893 1.7147 -0.1289 1.4500 0.7410 0.4410 -0.2669 -0.4303 +1305031467.7992 1.7151 -0.1240 1.4499 0.7402 0.4419 -0.2675 -0.4304 +1305031467.8092 1.7153 -0.1193 1.4499 0.7392 0.4423 -0.2683 -0.4312 +1305031467.8192 1.7156 -0.1142 1.4500 0.7383 0.4418 -0.2697 -0.4324 +1305031467.8293 1.7157 -0.1091 1.4499 0.7371 0.4415 -0.2712 -0.4337 +1305031467.8393 1.7154 -0.1039 1.4497 0.7357 0.4410 -0.2736 -0.4352 +1305031467.8493 1.7149 -0.0985 1.4497 0.7345 0.4398 -0.2762 -0.4369 +1305031467.8592 1.7145 -0.0932 1.4495 0.7329 0.4394 -0.2788 -0.4382 +1305031467.8692 1.7140 -0.0878 1.4492 0.7313 0.4397 -0.2816 -0.4389 +1305031467.8794 1.7134 -0.0826 1.4489 0.7300 0.4403 -0.2841 -0.4389 +1305031467.8892 1.7125 -0.0771 1.4484 0.7284 0.4416 -0.2865 -0.4387 +1305031467.8992 1.7116 -0.0719 1.4480 0.7274 0.4433 -0.2880 -0.4375 +1305031467.9093 1.7105 -0.0664 1.4476 0.7256 0.4446 -0.2901 -0.4378 +1305031467.9193 1.7093 -0.0608 1.4471 0.7236 0.4459 -0.2923 -0.4384 +1305031467.9293 1.7084 -0.0552 1.4467 0.7225 0.4464 -0.2936 -0.4389 +1305031467.9392 1.7071 -0.0495 1.4464 0.7207 0.4472 -0.2957 -0.4395 +1305031467.9493 1.7060 -0.0437 1.4460 0.7197 0.4476 -0.2966 -0.4401 +1305031467.9593 1.7045 -0.0378 1.4456 0.7178 0.4482 -0.2986 -0.4413 +1305031467.9692 1.7032 -0.0318 1.4452 0.7170 0.4479 -0.2997 -0.4421 +1305031467.9792 1.7017 -0.0260 1.4443 0.7167 0.4495 -0.2995 -0.4412 +1305031467.9895 1.6999 -0.0199 1.4437 0.7163 0.4503 -0.2997 -0.4408 +1305031467.9992 1.6983 -0.0138 1.4430 0.7162 0.4517 -0.2994 -0.4397 +1305031468.0092 1.6965 -0.0077 1.4424 0.7160 0.4527 -0.2991 -0.4393 +1305031468.0192 1.6949 -0.0015 1.4419 0.7157 0.4534 -0.2991 -0.4391 +1305031468.0292 1.6931 0.0042 1.4415 0.7157 0.4554 -0.2979 -0.4377 +1305031468.0392 1.6911 0.0102 1.4413 0.7137 0.4558 -0.2991 -0.4397 +1305031468.0494 1.6894 0.0165 1.4412 0.7121 0.4569 -0.3002 -0.4404 +1305031468.0592 1.6875 0.0226 1.4410 0.7102 0.4572 -0.3019 -0.4422 +1305031468.0693 1.6855 0.0289 1.4409 0.7090 0.4583 -0.3029 -0.4423 +1305031468.0793 1.6837 0.0352 1.4409 0.7084 0.4588 -0.3038 -0.4420 +1305031468.0892 1.6815 0.0414 1.4407 0.7080 0.4599 -0.3047 -0.4410 +1305031468.0992 1.6796 0.0480 1.4406 0.7076 0.4606 -0.3055 -0.4402 +1305031468.1092 1.6775 0.0541 1.4407 0.7075 0.4609 -0.3062 -0.4396 +1305031468.1192 1.6760 0.0603 1.4410 0.7091 0.4624 -0.3044 -0.4366 +1305031468.1292 1.6738 0.0666 1.4413 0.7081 0.4631 -0.3054 -0.4369 +1305031468.1392 1.6719 0.0731 1.4417 0.7070 0.4637 -0.3063 -0.4374 +1305031468.1493 1.6701 0.0796 1.4423 0.7059 0.4651 -0.3064 -0.4376 +1305031468.1593 1.6682 0.0860 1.4428 0.7054 0.4663 -0.3065 -0.4371 +1305031468.1693 1.6665 0.0924 1.4435 0.7049 0.4675 -0.3063 -0.4368 +1305031468.1797 1.6647 0.0990 1.4443 0.7048 0.4684 -0.3058 -0.4362 +1305031468.1893 1.6627 0.1057 1.4453 0.7041 0.4696 -0.3060 -0.4360 +1305031468.1993 1.6608 0.1124 1.4463 0.7043 0.4702 -0.3057 -0.4352 +1305031468.2092 1.6593 0.1193 1.4477 0.7050 0.4703 -0.3052 -0.4343 +1305031468.2192 1.6579 0.1261 1.4491 0.7060 0.4703 -0.3046 -0.4330 +1305031468.2292 1.6558 0.1331 1.4507 0.7061 0.4701 -0.3052 -0.4327 +1305031468.2392 1.6540 0.1401 1.4525 0.7060 0.4698 -0.3057 -0.4329 +1305031468.2493 1.6525 0.1470 1.4543 0.7072 0.4695 -0.3050 -0.4318 +1305031468.2593 1.6508 0.1539 1.4561 0.7075 0.4689 -0.3050 -0.4319 +1305031468.2694 1.6491 0.1609 1.4583 0.7079 0.4692 -0.3045 -0.4314 +1305031468.2792 1.6475 0.1676 1.4603 0.7084 0.4698 -0.3038 -0.4304 +1305031468.2893 1.6462 0.1743 1.4626 0.7089 0.4701 -0.3031 -0.4297 +1305031468.2992 1.6447 0.1810 1.4651 0.7094 0.4697 -0.3021 -0.4300 +1305031468.3093 1.6432 0.1877 1.4675 0.7096 0.4690 -0.3023 -0.4303 +1305031468.3192 1.6415 0.1943 1.4702 0.7095 0.4681 -0.3030 -0.4310 +1305031468.3293 1.6402 0.2008 1.4729 0.7098 0.4668 -0.3032 -0.4316 +1305031468.3392 1.6387 0.2073 1.4758 0.7104 0.4652 -0.3036 -0.4321 +1305031468.3493 1.6373 0.2138 1.4786 0.7110 0.4642 -0.3036 -0.4322 +1305031468.3592 1.6357 0.2201 1.4816 0.7115 0.4635 -0.3038 -0.4320 +1305031468.3694 1.6342 0.2262 1.4843 0.7127 0.4636 -0.3031 -0.4304 +1305031468.3792 1.6324 0.2323 1.4872 0.7132 0.4640 -0.3027 -0.4295 +1305031468.3892 1.6307 0.2384 1.4901 0.7137 0.4649 -0.3020 -0.4282 +1305031468.3992 1.6292 0.2442 1.4932 0.7144 0.4660 -0.3008 -0.4266 +1305031468.4092 1.6273 0.2497 1.4964 0.7150 0.4663 -0.3009 -0.4251 +1305031468.4192 1.6256 0.2553 1.4996 0.7155 0.4664 -0.3007 -0.4244 +1305031468.4292 1.6239 0.2608 1.5031 0.7160 0.4661 -0.3012 -0.4234 +1305031468.4392 1.6219 0.2662 1.5067 0.7164 0.4657 -0.3019 -0.4228 +1305031468.4493 1.6201 0.2718 1.5103 0.7168 0.4658 -0.3022 -0.4217 +1305031468.4592 1.6180 0.2769 1.5139 0.7178 0.4653 -0.3022 -0.4207 +1305031468.4694 1.6160 0.2820 1.5175 0.7186 0.4656 -0.3015 -0.4195 +1305031468.4792 1.6138 0.2867 1.5213 0.7197 0.4658 -0.3004 -0.4182 +1305031468.4893 1.6115 0.2916 1.5250 0.7203 0.4667 -0.2989 -0.4171 +1305031468.4993 1.6092 0.2961 1.5287 0.7205 0.4678 -0.2972 -0.4167 +1305031468.5092 1.6069 0.3003 1.5327 0.7202 0.4688 -0.2964 -0.4169 +1305031468.5193 1.6042 0.3044 1.5366 0.7191 0.4704 -0.2955 -0.4175 +1305031468.5292 1.6019 0.3083 1.5407 0.7176 0.4723 -0.2944 -0.4187 +1305031468.5392 1.5994 0.3123 1.5449 0.7157 0.4742 -0.2936 -0.4203 +1305031468.5493 1.5965 0.3160 1.5490 0.7133 0.4762 -0.2934 -0.4223 +1305031468.5592 1.5938 0.3196 1.5531 0.7116 0.4778 -0.2930 -0.4237 +1305031468.5694 1.5911 0.3233 1.5571 0.7099 0.4800 -0.2925 -0.4244 +1305031468.5792 1.5881 0.3267 1.5611 0.7090 0.4813 -0.2921 -0.4246 +1305031468.5893 1.5852 0.3301 1.5650 0.7093 0.4823 -0.2912 -0.4237 +1305031468.5992 1.5822 0.3334 1.5688 0.7093 0.4835 -0.2911 -0.4224 +1305031468.6092 1.5793 0.3366 1.5725 0.7106 0.4851 -0.2897 -0.4193 +1305031468.6192 1.5761 0.3395 1.5761 0.7116 0.4854 -0.2891 -0.4176 +1305031468.6292 1.5731 0.3425 1.5798 0.7121 0.4864 -0.2890 -0.4157 +1305031468.6392 1.5700 0.3457 1.5834 0.7115 0.4872 -0.2900 -0.4152 +1305031468.6493 1.5669 0.3484 1.5873 0.7109 0.4879 -0.2906 -0.4149 +1305031468.6592 1.5639 0.3511 1.5911 0.7094 0.4895 -0.2916 -0.4148 +1305031468.6692 1.5607 0.3537 1.5949 0.7080 0.4910 -0.2925 -0.4148 +1305031468.6792 1.5572 0.3563 1.5985 0.7057 0.4914 -0.2942 -0.4170 +1305031468.6893 1.5539 0.3588 1.6022 0.7039 0.4927 -0.2959 -0.4174 +1305031468.6992 1.5506 0.3611 1.6058 0.7026 0.4932 -0.2977 -0.4178 +1305031468.7092 1.5474 0.3636 1.6095 0.7013 0.4943 -0.2985 -0.4180 +1305031468.7192 1.5442 0.3657 1.6131 0.7006 0.4947 -0.3003 -0.4175 +1305031468.7292 1.5411 0.3680 1.6165 0.7002 0.4946 -0.3016 -0.4173 +1305031468.7392 1.5378 0.3703 1.6199 0.6993 0.4946 -0.3034 -0.4175 +1305031468.7493 1.5345 0.3723 1.6233 0.6991 0.4953 -0.3039 -0.4167 +1305031468.7593 1.5313 0.3745 1.6267 0.6987 0.4962 -0.3042 -0.4160 +1305031468.7692 1.5278 0.3765 1.6299 0.6973 0.4969 -0.3051 -0.4168 +1305031468.7798 1.5246 0.3785 1.6332 0.6962 0.4981 -0.3050 -0.4174 +1305031468.7892 1.5213 0.3803 1.6366 0.6942 0.4993 -0.3051 -0.4191 +1305031468.7993 1.5181 0.3822 1.6399 0.6922 0.5007 -0.3051 -0.4208 +1305031468.8101 1.5150 0.3840 1.6432 0.6902 0.5023 -0.3049 -0.4224 +1305031468.8192 1.5115 0.3858 1.6463 0.6876 0.5030 -0.3059 -0.4250 +1305031468.8307 1.5083 0.3876 1.6495 0.6863 0.5041 -0.3058 -0.4258 +1305031468.8393 1.5047 0.3892 1.6524 0.6854 0.5042 -0.3056 -0.4272 +1305031468.8492 1.5017 0.3909 1.6552 0.6854 0.5057 -0.3044 -0.4265 +1305031468.8592 1.4983 0.3926 1.6579 0.6858 0.5064 -0.3026 -0.4262 +1305031468.8702 1.4954 0.3942 1.6604 0.6863 0.5072 -0.3007 -0.4257 +1305031468.8793 1.4922 0.3958 1.6631 0.6878 0.5070 -0.2978 -0.4256 +1305031468.8892 1.4891 0.3974 1.6655 0.6885 0.5071 -0.2961 -0.4256 +1305031468.8992 1.4859 0.3992 1.6679 0.6893 0.5065 -0.2950 -0.4258 +1305031468.9092 1.4832 0.4009 1.6700 0.6910 0.5055 -0.2933 -0.4254 +1305031468.9192 1.4801 0.4026 1.6721 0.6931 0.5046 -0.2916 -0.4243 +1305031468.9292 1.4771 0.4043 1.6741 0.6952 0.5026 -0.2905 -0.4240 +1305031468.9392 1.4741 0.4059 1.6760 0.6979 0.5018 -0.2884 -0.4219 +1305031468.9493 1.4710 0.4075 1.6777 0.6998 0.5010 -0.2869 -0.4206 +1305031468.9592 1.4681 0.4092 1.6793 0.7013 0.5015 -0.2850 -0.4188 +1305031468.9692 1.4650 0.4109 1.6805 0.7031 0.5024 -0.2827 -0.4163 +1305031468.9792 1.4618 0.4126 1.6816 0.7043 0.5040 -0.2809 -0.4135 +1305031468.9892 1.4587 0.4142 1.6823 0.7071 0.5070 -0.2771 -0.4077 +1305031468.9992 1.4559 0.4159 1.6829 0.7091 0.5093 -0.2739 -0.4033 +1305031469.0092 1.4530 0.4176 1.6835 0.7116 0.5122 -0.2701 -0.3979 +1305031469.0192 1.4498 0.4193 1.6840 0.7136 0.5140 -0.2670 -0.3940 +1305031469.0292 1.4468 0.4212 1.6845 0.7149 0.5160 -0.2646 -0.3908 +1305031469.0392 1.4436 0.4229 1.6849 0.7155 0.5178 -0.2632 -0.3882 +1305031469.0492 1.4405 0.4246 1.6852 0.7157 0.5202 -0.2617 -0.3857 +1305031469.0592 1.4374 0.4262 1.6854 0.7161 0.5228 -0.2595 -0.3828 +1305031469.0692 1.4344 0.4280 1.6854 0.7160 0.5255 -0.2577 -0.3805 +1305031469.0793 1.4313 0.4297 1.6855 0.7163 0.5290 -0.2546 -0.3772 +1305031469.0892 1.4286 0.4315 1.6852 0.7169 0.5320 -0.2508 -0.3744 +1305031469.0992 1.4255 0.4335 1.6847 0.7170 0.5346 -0.2477 -0.3723 +1305031469.1092 1.4228 0.4354 1.6841 0.7183 0.5374 -0.2428 -0.3692 +1305031469.1192 1.4199 0.4374 1.6835 0.7192 0.5393 -0.2385 -0.3676 +1305031469.1292 1.4172 0.4393 1.6828 0.7202 0.5413 -0.2339 -0.3655 +1305031469.1392 1.4141 0.4414 1.6819 0.7209 0.5427 -0.2305 -0.3642 +1305031469.1492 1.4114 0.4435 1.6810 0.7219 0.5440 -0.2263 -0.3629 +1305031469.1593 1.4094 0.4454 1.6803 0.7243 0.5450 -0.2202 -0.3604 +1305031469.1692 1.4062 0.4475 1.6791 0.7248 0.5454 -0.2179 -0.3602 +1305031469.1793 1.4033 0.4496 1.6780 0.7256 0.5462 -0.2143 -0.3595 +1305031469.1893 1.4004 0.4517 1.6768 0.7262 0.5465 -0.2117 -0.3593 +1305031469.1992 1.3975 0.4539 1.6755 0.7263 0.5469 -0.2103 -0.3593 +1305031469.2092 1.3946 0.4559 1.6743 0.7269 0.5478 -0.2078 -0.3584 +1305031469.2192 1.3915 0.4580 1.6730 0.7268 0.5478 -0.2069 -0.3590 +1305031469.2292 1.3887 0.4597 1.6714 0.7269 0.5488 -0.2061 -0.3577 +1305031469.2392 1.3858 0.4617 1.6697 0.7269 0.5497 -0.2048 -0.3571 +1305031469.2492 1.3835 0.4636 1.6681 0.7275 0.5513 -0.2024 -0.3548 +1305031469.2593 1.3810 0.4655 1.6665 0.7278 0.5529 -0.2006 -0.3525 +1305031469.2692 1.3780 0.4672 1.6645 0.7285 0.5533 -0.1987 -0.3516 +1305031469.2793 1.3761 0.4691 1.6631 0.7297 0.5535 -0.1945 -0.3511 +1305031469.2892 1.3733 0.4709 1.6609 0.7304 0.5535 -0.1930 -0.3506 +1305031469.2993 1.3706 0.4725 1.6586 0.7310 0.5539 -0.1911 -0.3497 +1305031469.3092 1.3681 0.4741 1.6562 0.7316 0.5543 -0.1898 -0.3485 +1305031469.3192 1.3653 0.4755 1.6536 0.7318 0.5545 -0.1891 -0.3482 +1305031469.3292 1.3628 0.4770 1.6509 0.7325 0.5552 -0.1872 -0.3465 +1305031469.3392 1.3603 0.4785 1.6481 0.7332 0.5564 -0.1849 -0.3445 +1305031469.3493 1.3579 0.4799 1.6452 0.7335 0.5569 -0.1826 -0.3443 +1305031469.3592 1.3556 0.4813 1.6423 0.7348 0.5579 -0.1776 -0.3425 +1305031469.3692 1.3533 0.4827 1.6394 0.7355 0.5581 -0.1732 -0.3430 +1305031469.3795 1.3510 0.4840 1.6365 0.7358 0.5580 -0.1695 -0.3443 +1305031469.3892 1.3488 0.4853 1.6333 0.7359 0.5578 -0.1658 -0.3462 +1305031469.3992 1.3468 0.4867 1.6303 0.7361 0.5580 -0.1615 -0.3474 +1305031469.4092 1.3446 0.4879 1.6271 0.7357 0.5583 -0.1582 -0.3494 +1305031469.4192 1.3426 0.4892 1.6238 0.7354 0.5590 -0.1542 -0.3505 +1305031469.4293 1.3406 0.4904 1.6204 0.7351 0.5598 -0.1506 -0.3516 +1305031469.4392 1.3385 0.4916 1.6168 0.7347 0.5609 -0.1470 -0.3522 +1305031469.4493 1.3367 0.4929 1.6134 0.7341 0.5620 -0.1437 -0.3530 +1305031469.4592 1.3348 0.4941 1.6098 0.7342 0.5626 -0.1403 -0.3533 +1305031469.4692 1.3331 0.4951 1.6061 0.7344 0.5632 -0.1373 -0.3530 +1305031469.4792 1.3308 0.4964 1.6022 0.7331 0.5632 -0.1379 -0.3555 +1305031469.4893 1.3295 0.4975 1.5986 0.7337 0.5633 -0.1359 -0.3547 +1305031469.4993 1.3273 0.4986 1.5945 0.7335 0.5643 -0.1362 -0.3536 +1305031469.5092 1.3255 0.4997 1.5905 0.7335 0.5646 -0.1364 -0.3530 +1305031469.5192 1.3242 0.5005 1.5865 0.7347 0.5646 -0.1351 -0.3509 +1305031469.5294 1.3225 0.5017 1.5822 0.7347 0.5651 -0.1354 -0.3500 +1305031469.5392 1.3207 0.5026 1.5777 0.7346 0.5663 -0.1358 -0.3482 +1305031469.5492 1.3195 0.5034 1.5735 0.7360 0.5663 -0.1342 -0.3459 +1305031469.5592 1.3181 0.5043 1.5690 0.7368 0.5667 -0.1334 -0.3437 +1305031469.5692 1.3166 0.5052 1.5644 0.7374 0.5663 -0.1338 -0.3431 +1305031469.5792 1.3153 0.5059 1.5596 0.7385 0.5668 -0.1330 -0.3401 +1305031469.5892 1.3138 0.5068 1.5548 0.7389 0.5672 -0.1334 -0.3383 +1305031469.5992 1.3124 0.5075 1.5500 0.7403 0.5669 -0.1328 -0.3361 +1305031469.6092 1.3112 0.5080 1.5451 0.7419 0.5666 -0.1313 -0.3336 +1305031469.6193 1.3098 0.5086 1.5401 0.7430 0.5668 -0.1303 -0.3313 +1305031469.6292 1.3086 0.5092 1.5353 0.7442 0.5659 -0.1290 -0.3304 +1305031469.6392 1.3073 0.5095 1.5304 0.7454 0.5655 -0.1272 -0.3292 +1305031469.6493 1.3058 0.5098 1.5255 0.7461 0.5651 -0.1263 -0.3287 +1305031469.6592 1.3044 0.5101 1.5206 0.7468 0.5646 -0.1252 -0.3283 +1305031469.6692 1.3030 0.5102 1.5156 0.7477 0.5643 -0.1241 -0.3274 +1305031469.6792 1.3018 0.5103 1.5108 0.7485 0.5640 -0.1226 -0.3265 +1305031469.6893 1.3003 0.5101 1.5057 0.7495 0.5636 -0.1213 -0.3254 +1305031469.6992 1.2989 0.5101 1.5006 0.7504 0.5631 -0.1198 -0.3247 +1305031469.7092 1.2976 0.5098 1.4956 0.7517 0.5622 -0.1183 -0.3239 +1305031469.7192 1.2960 0.5094 1.4904 0.7529 0.5613 -0.1168 -0.3231 +1305031469.7292 1.2947 0.5089 1.4856 0.7543 0.5603 -0.1152 -0.3222 +1305031469.7392 1.2932 0.5082 1.4804 0.7556 0.5593 -0.1141 -0.3212 +1305031469.7492 1.2919 0.5074 1.4752 0.7571 0.5587 -0.1121 -0.3194 +1305031469.7595 1.2904 0.5065 1.4702 0.7583 0.5578 -0.1113 -0.3185 +1305031469.7692 1.2891 0.5056 1.4650 0.7596 0.5574 -0.1106 -0.3163 +1305031469.7792 1.2874 0.5043 1.4598 0.7606 0.5572 -0.1101 -0.3145 +1305031469.7892 1.2859 0.5029 1.4547 0.7616 0.5563 -0.1104 -0.3134 +1305031469.7992 1.2846 0.5014 1.4498 0.7625 0.5563 -0.1100 -0.3114 +1305031469.8092 1.2830 0.4998 1.4447 0.7633 0.5559 -0.1105 -0.3101 +1305031469.8195 1.2816 0.4980 1.4396 0.7639 0.5557 -0.1107 -0.3089 +1305031469.8292 1.2802 0.4961 1.4346 0.7651 0.5555 -0.1106 -0.3064 +1305031469.8392 1.2788 0.4940 1.4295 0.7663 0.5551 -0.1103 -0.3042 +1305031469.8493 1.2775 0.4919 1.4245 0.7671 0.5552 -0.1100 -0.3019 +1305031469.8592 1.2761 0.4897 1.4195 0.7679 0.5550 -0.1103 -0.3003 +1305031469.8693 1.2747 0.4873 1.4146 0.7686 0.5544 -0.1109 -0.2994 +1305031469.8792 1.2734 0.4849 1.4097 0.7695 0.5541 -0.1105 -0.2978 +1305031469.8892 1.2718 0.4823 1.4047 0.7703 0.5530 -0.1112 -0.2973 +1305031469.8992 1.2705 0.4795 1.3999 0.7714 0.5526 -0.1110 -0.2955 +1305031469.9093 1.2690 0.4767 1.3952 0.7724 0.5519 -0.1109 -0.2941 +1305031469.9192 1.2676 0.4735 1.3906 0.7731 0.5514 -0.1115 -0.2928 +1305031469.9292 1.2659 0.4706 1.3858 0.7732 0.5513 -0.1127 -0.2923 +1305031469.9393 1.2646 0.4673 1.3813 0.7736 0.5510 -0.1133 -0.2917 +1305031469.9493 1.2631 0.4639 1.3767 0.7740 0.5506 -0.1145 -0.2910 +1305031469.9592 1.2615 0.4606 1.3723 0.7744 0.5501 -0.1151 -0.2908 +1305031469.9693 1.2599 0.4570 1.3678 0.7749 0.5497 -0.1154 -0.2898 +1305031469.9795 1.2584 0.4535 1.3635 0.7753 0.5494 -0.1153 -0.2894 +1305031469.9892 1.2567 0.4498 1.3591 0.7755 0.5489 -0.1167 -0.2891 +1305031469.9992 1.2552 0.4460 1.3550 0.7760 0.5489 -0.1166 -0.2880 +1305031470.0092 1.2537 0.4419 1.3508 0.7763 0.5487 -0.1171 -0.2872 +1305031470.0193 1.2520 0.4382 1.3467 0.7763 0.5489 -0.1175 -0.2868 +1305031470.0292 1.2508 0.4340 1.3429 0.7766 0.5489 -0.1173 -0.2859 +1305031470.0392 1.2492 0.4299 1.3391 0.7770 0.5489 -0.1168 -0.2853 +1305031470.0492 1.2478 0.4258 1.3354 0.7772 0.5487 -0.1165 -0.2852 +1305031470.0592 1.2463 0.4216 1.3317 0.7774 0.5486 -0.1166 -0.2848 +1305031470.0692 1.2449 0.4174 1.3283 0.7778 0.5476 -0.1167 -0.2856 +1305031470.0792 1.2435 0.4129 1.3248 0.7786 0.5472 -0.1160 -0.2845 +1305031470.0892 1.2419 0.4087 1.3213 0.7788 0.5467 -0.1170 -0.2845 +1305031470.0992 1.2407 0.4042 1.3181 0.7796 0.5463 -0.1164 -0.2831 +1305031470.1092 1.2394 0.3996 1.3149 0.7809 0.5457 -0.1157 -0.2811 +1305031470.1192 1.2380 0.3951 1.3118 0.7816 0.5453 -0.1152 -0.2802 +1305031470.1292 1.2365 0.3906 1.3087 0.7822 0.5447 -0.1153 -0.2796 +1305031470.1392 1.2351 0.3860 1.3057 0.7829 0.5439 -0.1156 -0.2791 +1305031470.1492 1.2336 0.3814 1.3027 0.7835 0.5433 -0.1160 -0.2785 +1305031470.1592 1.2323 0.3769 1.3001 0.7841 0.5428 -0.1161 -0.2777 +1305031470.1692 1.2309 0.3722 1.2973 0.7846 0.5419 -0.1170 -0.2775 +1305031470.1792 1.2293 0.3675 1.2947 0.7849 0.5413 -0.1183 -0.2774 +1305031470.1892 1.2280 0.3629 1.2921 0.7861 0.5405 -0.1177 -0.2760 +1305031470.1992 1.2267 0.3583 1.2896 0.7870 0.5399 -0.1175 -0.2744 +1305031470.2092 1.2252 0.3535 1.2871 0.7880 0.5390 -0.1175 -0.2733 +1305031470.2192 1.2236 0.3489 1.2845 0.7889 0.5381 -0.1175 -0.2724 +1305031470.2292 1.2220 0.3442 1.2820 0.7898 0.5372 -0.1173 -0.2717 +1305031470.2392 1.2204 0.3396 1.2795 0.7908 0.5365 -0.1171 -0.2705 +1305031470.2492 1.2190 0.3349 1.2772 0.7917 0.5361 -0.1164 -0.2687 +1305031470.2592 1.2173 0.3302 1.2746 0.7927 0.5353 -0.1166 -0.2675 +1305031470.2692 1.2159 0.3255 1.2725 0.7939 0.5347 -0.1151 -0.2656 +1305031470.2792 1.2140 0.3209 1.2700 0.7947 0.5341 -0.1147 -0.2648 +1305031470.2892 1.2124 0.3163 1.2677 0.7955 0.5338 -0.1141 -0.2632 +1305031470.2992 1.2107 0.3117 1.2654 0.7965 0.5332 -0.1134 -0.2615 +1305031470.3092 1.2090 0.3071 1.2632 0.7976 0.5327 -0.1128 -0.2593 +1305031470.3192 1.2073 0.3025 1.2610 0.7985 0.5321 -0.1128 -0.2579 +1305031470.3292 1.2057 0.2979 1.2590 0.7998 0.5311 -0.1125 -0.2559 +1305031470.3392 1.2040 0.2932 1.2569 0.8008 0.5301 -0.1131 -0.2548 +1305031470.3492 1.2023 0.2886 1.2551 0.8018 0.5293 -0.1133 -0.2531 +1305031470.3592 1.2005 0.2840 1.2535 0.8031 0.5283 -0.1132 -0.2511 +1305031470.3692 1.1988 0.2794 1.2517 0.8041 0.5274 -0.1136 -0.2498 +1305031470.3792 1.1972 0.2748 1.2501 0.8050 0.5263 -0.1139 -0.2490 +1305031470.3892 1.1952 0.2703 1.2484 0.8053 0.5260 -0.1145 -0.2483 +1305031470.3992 1.1934 0.2657 1.2468 0.8053 0.5263 -0.1148 -0.2474 +1305031470.4092 1.1917 0.2611 1.2453 0.8055 0.5266 -0.1147 -0.2466 +1305031470.4192 1.1900 0.2567 1.2442 0.8054 0.5269 -0.1141 -0.2461 +1305031470.4292 1.1881 0.2526 1.2428 0.8046 0.5275 -0.1152 -0.2470 +1305031470.4392 1.1862 0.2481 1.2416 0.8047 0.5277 -0.1156 -0.2465 +1305031470.4492 1.1843 0.2439 1.2403 0.8046 0.5275 -0.1160 -0.2469 +1305031470.4592 1.1824 0.2396 1.2393 0.8046 0.5273 -0.1164 -0.2471 +1305031470.4692 1.1806 0.2355 1.2383 0.8048 0.5270 -0.1168 -0.2468 +1305031470.4792 1.1786 0.2314 1.2373 0.8049 0.5266 -0.1176 -0.2469 +1305031470.4892 1.1768 0.2273 1.2363 0.8053 0.5260 -0.1179 -0.2467 +1305031470.4992 1.1750 0.2233 1.2353 0.8053 0.5261 -0.1182 -0.2466 +1305031470.5092 1.1731 0.2195 1.2342 0.8052 0.5259 -0.1183 -0.2471 +1305031470.5192 1.1712 0.2155 1.2333 0.8052 0.5261 -0.1181 -0.2468 +1305031470.5292 1.1693 0.2119 1.2322 0.8052 0.5262 -0.1178 -0.2466 +1305031470.5392 1.1673 0.2083 1.2311 0.8054 0.5259 -0.1178 -0.2465 +1305031470.5492 1.1652 0.2046 1.2300 0.8057 0.5253 -0.1177 -0.2469 +1305031470.5592 1.1635 0.2012 1.2292 0.8064 0.5253 -0.1165 -0.2455 +1305031470.5692 1.1615 0.1977 1.2283 0.8070 0.5243 -0.1168 -0.2455 +1305031470.5795 1.1595 0.1944 1.2273 0.8076 0.5233 -0.1172 -0.2456 +1305031470.5892 1.1576 0.1910 1.2264 0.8085 0.5220 -0.1174 -0.2453 +1305031470.5992 1.1557 0.1877 1.2254 0.8094 0.5209 -0.1172 -0.2444 +1305031470.6092 1.1538 0.1847 1.2244 0.8102 0.5200 -0.1174 -0.2436 +1305031470.6192 1.1519 0.1813 1.2237 0.8115 0.5189 -0.1165 -0.2420 +1305031470.6292 1.1499 0.1784 1.2227 0.8120 0.5180 -0.1170 -0.2419 +1305031470.6392 1.1479 0.1754 1.2217 0.8130 0.5167 -0.1172 -0.2416 +1305031470.6492 1.1458 0.1725 1.2209 0.8136 0.5160 -0.1175 -0.2408 +1305031470.6592 1.1437 0.1695 1.2200 0.8143 0.5148 -0.1179 -0.2408 +1305031470.6692 1.1416 0.1666 1.2190 0.8152 0.5142 -0.1177 -0.2391 +1305031470.6792 1.1397 0.1638 1.2182 0.8158 0.5137 -0.1178 -0.2381 +1305031470.6892 1.1375 0.1609 1.2174 0.8165 0.5132 -0.1179 -0.2368 +1305031470.6992 1.1355 0.1584 1.2166 0.8168 0.5128 -0.1182 -0.2362 +1305031470.7092 1.1334 0.1555 1.2160 0.8173 0.5119 -0.1187 -0.2364 +1305031470.7192 1.1312 0.1530 1.2154 0.8174 0.5109 -0.1197 -0.2377 +1305031470.7292 1.1293 0.1505 1.2149 0.8182 0.5098 -0.1188 -0.2377 +1305031470.7392 1.1275 0.1481 1.2145 0.8192 0.5084 -0.1183 -0.2375 +1305031470.7495 1.1258 0.1455 1.2139 0.8207 0.5068 -0.1168 -0.2367 +1305031470.7592 1.1238 0.1431 1.2135 0.8221 0.5054 -0.1149 -0.2358 +1305031470.7695 1.1221 0.1408 1.2130 0.8233 0.5038 -0.1137 -0.2355 +1305031470.7792 1.1201 0.1386 1.2124 0.8241 0.5024 -0.1128 -0.2359 +1305031470.7892 1.1181 0.1362 1.2121 0.8248 0.5014 -0.1124 -0.2360 +1305031470.7993 1.1161 0.1338 1.2120 0.8256 0.4999 -0.1125 -0.2364 +1305031470.8092 1.1142 0.1316 1.2118 0.8259 0.4988 -0.1132 -0.2372 +1305031470.8192 1.1122 0.1294 1.2119 0.8262 0.4973 -0.1142 -0.2388 +1305031470.8292 1.1101 0.1271 1.2118 0.8263 0.4960 -0.1155 -0.2406 +1305031470.8392 1.1081 0.1247 1.2119 0.8267 0.4947 -0.1164 -0.2417 +1305031470.8492 1.1062 0.1224 1.2122 0.8273 0.4935 -0.1167 -0.2417 +1305031470.8592 1.1042 0.1201 1.2123 0.8274 0.4924 -0.1176 -0.2431 +1305031470.8692 1.1022 0.1179 1.2125 0.8276 0.4911 -0.1187 -0.2444 +1305031470.8792 1.1004 0.1157 1.2128 0.8282 0.4902 -0.1190 -0.2443 +1305031470.8892 1.0981 0.1136 1.2129 0.8282 0.4891 -0.1213 -0.2453 +1305031470.8992 1.0962 0.1112 1.2135 0.8287 0.4880 -0.1218 -0.2455 +1305031470.9092 1.0942 0.1090 1.2140 0.8288 0.4869 -0.1235 -0.2463 +1305031470.9192 1.0921 0.1067 1.2146 0.8289 0.4859 -0.1252 -0.2474 +1305031470.9292 1.0901 0.1043 1.2153 0.8288 0.4848 -0.1271 -0.2488 +1305031470.9392 1.0880 0.1021 1.2163 0.8282 0.4838 -0.1295 -0.2514 +1305031470.9492 1.0860 0.1001 1.2172 0.8275 0.4830 -0.1313 -0.2545 +1305031470.9592 1.0840 0.0980 1.2182 0.8268 0.4825 -0.1328 -0.2567 +1305031470.9692 1.0820 0.0958 1.2191 0.8268 0.4814 -0.1338 -0.2582 +1305031470.9792 1.0800 0.0938 1.2200 0.8269 0.4803 -0.1343 -0.2600 +1305031470.9891 1.0778 0.0919 1.2209 0.8266 0.4793 -0.1348 -0.2622 +1305031470.9992 1.0759 0.0899 1.2219 0.8267 0.4781 -0.1349 -0.2642 +1305031471.0092 1.0739 0.0881 1.2229 0.8264 0.4769 -0.1354 -0.2669 +1305031471.0192 1.0718 0.0864 1.2239 0.8261 0.4757 -0.1363 -0.2696 +1305031471.0292 1.0697 0.0845 1.2250 0.8260 0.4742 -0.1367 -0.2723 +1305031471.0392 1.0678 0.0828 1.2264 0.8258 0.4725 -0.1372 -0.2755 +1305031471.0492 1.0658 0.0811 1.2274 0.8260 0.4711 -0.1375 -0.2775 +1305031471.0592 1.0641 0.0796 1.2287 0.8263 0.4692 -0.1377 -0.2796 +1305031471.0692 1.0621 0.0780 1.2297 0.8263 0.4673 -0.1387 -0.2822 +1305031471.0792 1.0600 0.0764 1.2307 0.8266 0.4655 -0.1400 -0.2837 +1305031471.0892 1.0582 0.0748 1.2319 0.8273 0.4640 -0.1404 -0.2840 +1305031471.0992 1.0564 0.0733 1.2329 0.8275 0.4620 -0.1422 -0.2857 +1305031471.1092 1.0548 0.0716 1.2340 0.8282 0.4602 -0.1431 -0.2859 +1305031471.1192 1.0530 0.0701 1.2351 0.8286 0.4584 -0.1443 -0.2873 +1305031471.1292 1.0511 0.0687 1.2361 0.8286 0.4563 -0.1458 -0.2898 +1305031471.1392 1.0495 0.0672 1.2370 0.8292 0.4544 -0.1466 -0.2907 +1305031471.1492 1.0478 0.0658 1.2379 0.8298 0.4527 -0.1470 -0.2914 +1305031471.1592 1.0461 0.0645 1.2386 0.8301 0.4511 -0.1475 -0.2927 +1305031471.1692 1.0445 0.0631 1.2394 0.8311 0.4489 -0.1472 -0.2934 +1305031471.1793 1.0426 0.0618 1.2399 0.8319 0.4467 -0.1473 -0.2943 +1305031471.1892 1.0409 0.0607 1.2404 0.8326 0.4451 -0.1471 -0.2950 +1305031471.1992 1.0391 0.0593 1.2409 0.8337 0.4432 -0.1465 -0.2951 +1305031471.2092 1.0371 0.0580 1.2414 0.8345 0.4417 -0.1462 -0.2953 +1305031471.2192 1.0355 0.0567 1.2419 0.8356 0.4409 -0.1449 -0.2940 +1305031471.2292 1.0337 0.0553 1.2422 0.8362 0.4396 -0.1447 -0.2943 +1305031471.2392 1.0318 0.0540 1.2425 0.8367 0.4387 -0.1443 -0.2943 +1305031471.2492 1.0299 0.0527 1.2429 0.8372 0.4374 -0.1440 -0.2950 +1305031471.2592 1.0285 0.0514 1.2435 0.8383 0.4365 -0.1434 -0.2937 +1305031471.2692 1.0268 0.0501 1.2440 0.8388 0.4348 -0.1434 -0.2946 +1305031471.2792 1.0252 0.0489 1.2444 0.8394 0.4330 -0.1436 -0.2956 +1305031471.2892 1.0238 0.0477 1.2451 0.8399 0.4313 -0.1435 -0.2966 +1305031471.2992 1.0224 0.0465 1.2458 0.8404 0.4293 -0.1432 -0.2981 +1305031471.3092 1.0210 0.0455 1.2463 0.8405 0.4277 -0.1430 -0.3002 +1305031471.3192 1.0197 0.0444 1.2469 0.8411 0.4261 -0.1422 -0.3013 +1305031471.3292 1.0184 0.0434 1.2475 0.8416 0.4249 -0.1405 -0.3023 +1305031471.3406 1.0173 0.0423 1.2480 0.8425 0.4236 -0.1383 -0.3027 +1305031471.3492 1.0161 0.0413 1.2485 0.8433 0.4220 -0.1365 -0.3035 +1305031471.3592 1.0153 0.0404 1.2491 0.8449 0.4201 -0.1338 -0.3031 +1305031471.3692 1.0143 0.0392 1.2500 0.8460 0.4183 -0.1315 -0.3033 +1305031471.3792 1.0131 0.0383 1.2507 0.8464 0.4163 -0.1315 -0.3049 +1305031471.3892 1.0120 0.0375 1.2515 0.8465 0.4143 -0.1313 -0.3074 +1305031471.3992 1.0111 0.0365 1.2524 0.8472 0.4123 -0.1315 -0.3082 +1305031471.4093 1.0100 0.0356 1.2533 0.8473 0.4105 -0.1327 -0.3097 +1305031471.4192 1.0090 0.0346 1.2540 0.8478 0.4087 -0.1336 -0.3103 +1305031471.4293 1.0079 0.0334 1.2548 0.8486 0.4072 -0.1341 -0.3101 +1305031471.4392 1.0068 0.0324 1.2555 0.8493 0.4059 -0.1343 -0.3096 +1305031471.4492 1.0056 0.0315 1.2562 0.8496 0.4050 -0.1349 -0.3098 +1305031471.4593 1.0045 0.0303 1.2568 0.8503 0.4040 -0.1351 -0.3090 +1305031471.4692 1.0034 0.0290 1.2575 0.8511 0.4031 -0.1351 -0.3080 +1305031471.4792 1.0025 0.0281 1.2581 0.8517 0.4014 -0.1351 -0.3086 +1305031471.4892 1.0016 0.0270 1.2588 0.8525 0.4002 -0.1350 -0.3079 +1305031471.4992 1.0006 0.0258 1.2595 0.8532 0.3987 -0.1352 -0.3077 +1305031471.5092 0.9995 0.0248 1.2601 0.8536 0.3971 -0.1360 -0.3086 +1305031471.5192 0.9986 0.0235 1.2607 0.8543 0.3961 -0.1358 -0.3080 +1305031471.5292 0.9978 0.0223 1.2615 0.8547 0.3953 -0.1358 -0.3079 +1305031471.5392 0.9971 0.0210 1.2622 0.8552 0.3941 -0.1355 -0.3081 +1305031471.5492 0.9964 0.0197 1.2629 0.8558 0.3934 -0.1347 -0.3077 +1305031471.5592 0.9957 0.0185 1.2635 0.8564 0.3924 -0.1337 -0.3078 +1305031471.5692 0.9952 0.0173 1.2642 0.8572 0.3913 -0.1322 -0.3077 +1305031471.5792 0.9946 0.0160 1.2650 0.8577 0.3900 -0.1311 -0.3083 +1305031471.5892 0.9941 0.0150 1.2656 0.8580 0.3888 -0.1302 -0.3093 +1305031471.5992 0.9935 0.0138 1.2663 0.8583 0.3876 -0.1293 -0.3105 +1305031471.6092 0.9931 0.0127 1.2670 0.8587 0.3866 -0.1283 -0.3109 +1305031471.6191 0.9927 0.0117 1.2678 0.8592 0.3858 -0.1269 -0.3112 +1305031471.6291 0.9924 0.0105 1.2686 0.8598 0.3844 -0.1255 -0.3117 +1305031471.6392 0.9921 0.0096 1.2693 0.8601 0.3830 -0.1249 -0.3129 +1305031471.6492 0.9918 0.0086 1.2700 0.8603 0.3816 -0.1241 -0.3144 +1305031471.6592 0.9916 0.0075 1.2706 0.8612 0.3798 -0.1234 -0.3145 +1305031471.6691 0.9914 0.0066 1.2714 0.8617 0.3781 -0.1228 -0.3153 +1305031471.6791 0.9913 0.0057 1.2721 0.8623 0.3763 -0.1223 -0.3161 +1305031471.6892 0.9910 0.0049 1.2726 0.8629 0.3747 -0.1221 -0.3165 +1305031471.6992 0.9909 0.0039 1.2732 0.8637 0.3732 -0.1213 -0.3162 +1305031471.7098 0.9907 0.0031 1.2735 0.8645 0.3719 -0.1209 -0.3158 +1305031471.7191 0.9906 0.0023 1.2739 0.8654 0.3703 -0.1201 -0.3156 +1305031471.7292 0.9905 0.0015 1.2742 0.8666 0.3682 -0.1191 -0.3151 +1305031471.7391 0.9903 0.0008 1.2744 0.8674 0.3661 -0.1189 -0.3153 +1305031471.7492 0.9903 0.0001 1.2747 0.8685 0.3639 -0.1183 -0.3150 +1305031471.7592 0.9904 -0.0005 1.2750 0.8696 0.3609 -0.1175 -0.3157 +1305031471.7692 0.9903 -0.0012 1.2752 0.8705 0.3578 -0.1171 -0.3171 +1305031471.7791 0.9904 -0.0018 1.2754 0.8714 0.3552 -0.1164 -0.3178 +1305031471.7892 0.9905 -0.0025 1.2755 0.8725 0.3528 -0.1149 -0.3179 +1305031471.7992 0.9905 -0.0033 1.2755 0.8739 0.3508 -0.1134 -0.3169 +1305031471.8092 0.9903 -0.0041 1.2752 0.8752 0.3486 -0.1126 -0.3159 +1305031471.8192 0.9902 -0.0049 1.2750 0.8764 0.3472 -0.1117 -0.3144 +1305031471.8292 0.9900 -0.0058 1.2746 0.8776 0.3453 -0.1111 -0.3135 +1305031471.8393 0.9899 -0.0067 1.2742 0.8787 0.3431 -0.1108 -0.3129 +1305031471.8493 0.9895 -0.0075 1.2739 0.8794 0.3410 -0.1109 -0.3132 +1305031471.8591 0.9894 -0.0085 1.2735 0.8808 0.3386 -0.1101 -0.3122 +1305031471.8692 0.9890 -0.0093 1.2730 0.8815 0.3363 -0.1098 -0.3126 +1305031471.8792 0.9888 -0.0104 1.2725 0.8832 0.3343 -0.1085 -0.3105 +1305031471.8895 0.9883 -0.0112 1.2720 0.8843 0.3325 -0.1076 -0.3097 +1305031471.8992 0.9878 -0.0123 1.2713 0.8855 0.3305 -0.1060 -0.3089 +1305031471.9092 0.9875 -0.0132 1.2708 0.8869 0.3292 -0.1043 -0.3068 +1305031471.9192 0.9870 -0.0144 1.2701 0.8879 0.3277 -0.1028 -0.3060 +1305031471.9292 0.9866 -0.0156 1.2696 0.8888 0.3267 -0.1005 -0.3052 +1305031471.9392 0.9859 -0.0166 1.2691 0.8893 0.3248 -0.0991 -0.3063 +1305031471.9492 0.9854 -0.0176 1.2688 0.8895 0.3236 -0.0973 -0.3075 +1305031471.9592 0.9850 -0.0186 1.2684 0.8897 0.3221 -0.0958 -0.3090 +1305031471.9692 0.9845 -0.0196 1.2680 0.8903 0.3203 -0.0935 -0.3100 +1305031471.9793 0.9838 -0.0208 1.2671 0.8909 0.3184 -0.0919 -0.3105 +1305031471.9892 0.9831 -0.0219 1.2665 0.8921 0.3171 -0.0897 -0.3092 +1305031471.9992 0.9824 -0.0230 1.2655 0.8930 0.3157 -0.0877 -0.3084 +1305031472.0092 0.9817 -0.0241 1.2645 0.8945 0.3147 -0.0856 -0.3059 +1305031472.0192 0.9810 -0.0254 1.2638 0.8955 0.3142 -0.0836 -0.3039 +1305031472.0292 0.9803 -0.0266 1.2631 0.8965 0.3129 -0.0822 -0.3027 +1305031472.0392 0.9798 -0.0277 1.2625 0.8967 0.3118 -0.0813 -0.3035 +1305031472.0492 0.9790 -0.0287 1.2619 0.8969 0.3098 -0.0809 -0.3052 +1305031472.0592 0.9782 -0.0298 1.2614 0.8972 0.3080 -0.0803 -0.3062 +1305031472.0692 0.9777 -0.0308 1.2608 0.8979 0.3056 -0.0796 -0.3067 +1305031472.0793 0.9769 -0.0316 1.2602 0.8982 0.3032 -0.0789 -0.3082 +1305031472.0892 0.9761 -0.0329 1.2595 0.8995 0.3019 -0.0774 -0.3062 +1305031472.0992 0.9753 -0.0339 1.2587 0.9006 0.3010 -0.0761 -0.3042 +1305031472.1092 0.9741 -0.0350 1.2577 0.9012 0.3001 -0.0750 -0.3036 +1305031472.1192 0.9731 -0.0360 1.2569 0.9018 0.2999 -0.0743 -0.3021 +1305031472.1291 0.9721 -0.0371 1.2562 0.9026 0.2994 -0.0740 -0.3002 +1305031472.1392 0.9711 -0.0382 1.2556 0.9031 0.2987 -0.0734 -0.2995 +1305031472.1492 0.9704 -0.0392 1.2552 0.9038 0.2979 -0.0731 -0.2985 +1305031472.1592 0.9694 -0.0400 1.2550 0.9038 0.2966 -0.0733 -0.2996 +1305031472.1692 0.9686 -0.0409 1.2549 0.9039 0.2951 -0.0738 -0.3008 +1305031472.1792 0.9677 -0.0418 1.2547 0.9039 0.2931 -0.0743 -0.3024 +1305031472.1892 0.9668 -0.0425 1.2546 0.9040 0.2916 -0.0750 -0.3037 +1305031472.1991 0.9662 -0.0432 1.2546 0.9040 0.2908 -0.0750 -0.3042 +1305031472.2092 0.9654 -0.0439 1.2544 0.9040 0.2899 -0.0755 -0.3050 +1305031472.2192 0.9645 -0.0449 1.2545 0.9044 0.2890 -0.0751 -0.3047 +1305031472.2292 0.9638 -0.0454 1.2544 0.9044 0.2885 -0.0748 -0.3054 +1305031472.2394 0.9631 -0.0461 1.2544 0.9041 0.2877 -0.0747 -0.3070 +1305031472.2492 0.9626 -0.0468 1.2547 0.9042 0.2871 -0.0745 -0.3073 +1305031472.2591 0.9621 -0.0473 1.2549 0.9037 0.2862 -0.0748 -0.3095 +1305031472.2692 0.9615 -0.0477 1.2554 0.9032 0.2850 -0.0748 -0.3122 +1305031472.2791 0.9611 -0.0480 1.2557 0.9027 0.2839 -0.0753 -0.3143 +1305031472.2892 0.9608 -0.0484 1.2561 0.9023 0.2828 -0.0756 -0.3165 +1305031472.2991 0.9607 -0.0489 1.2568 0.9023 0.2822 -0.0750 -0.3171 +1305031472.3092 0.9600 -0.0492 1.2571 0.9017 0.2817 -0.0759 -0.3191 +1305031472.3192 0.9597 -0.0494 1.2575 0.9017 0.2814 -0.0761 -0.3195 +1305031472.3292 0.9593 -0.0495 1.2578 0.9014 0.2813 -0.0763 -0.3203 +1305031472.3392 0.9590 -0.0496 1.2582 0.9016 0.2812 -0.0762 -0.3197 +1305031472.3492 0.9586 -0.0497 1.2585 0.9020 0.2809 -0.0761 -0.3189 +1305031472.3591 0.9582 -0.0497 1.2588 0.9023 0.2807 -0.0761 -0.3181 +1305031472.3692 0.9578 -0.0498 1.2591 0.9026 0.2805 -0.0765 -0.3174 +1305031472.3792 0.9573 -0.0497 1.2596 0.9025 0.2804 -0.0773 -0.3175 +1305031472.3892 0.9569 -0.0495 1.2602 0.9025 0.2801 -0.0783 -0.3177 +1305031472.3992 0.9564 -0.0493 1.2607 0.9023 0.2798 -0.0795 -0.3181 +1305031472.4092 0.9560 -0.0491 1.2613 0.9020 0.2800 -0.0805 -0.3185 +1305031472.4192 0.9554 -0.0488 1.2619 0.9017 0.2804 -0.0814 -0.3188 +1305031472.4291 0.9549 -0.0484 1.2624 0.9015 0.2802 -0.0820 -0.3196 +1305031472.4392 0.9546 -0.0482 1.2630 0.9014 0.2806 -0.0823 -0.3194 +1305031472.4491 0.9542 -0.0478 1.2637 0.9015 0.2809 -0.0823 -0.3188 +1305031472.4592 0.9538 -0.0473 1.2642 0.9014 0.2808 -0.0823 -0.3193 +1305031472.4691 0.9535 -0.0468 1.2647 0.9013 0.2809 -0.0817 -0.3194 +1305031472.4792 0.9532 -0.0461 1.2653 0.9015 0.2808 -0.0807 -0.3194 +1305031472.4892 0.9531 -0.0457 1.2660 0.9019 0.2804 -0.0796 -0.3187 +1305031472.4991 0.9529 -0.0453 1.2666 0.9021 0.2799 -0.0793 -0.3186 +1305031472.5093 0.9526 -0.0447 1.2672 0.9021 0.2794 -0.0791 -0.3192 +1305031472.5192 0.9527 -0.0441 1.2681 0.9019 0.2792 -0.0790 -0.3199 +1305031472.5291 0.9528 -0.0435 1.2691 0.9019 0.2788 -0.0791 -0.3204 +1305031472.5392 0.9527 -0.0429 1.2701 0.9012 0.2785 -0.0804 -0.3222 +1305031472.5492 0.9527 -0.0422 1.2709 0.9007 0.2779 -0.0815 -0.3237 +1305031472.5592 0.9527 -0.0416 1.2719 0.9001 0.2775 -0.0827 -0.3254 +1305031472.5692 0.9526 -0.0410 1.2729 0.8999 0.2771 -0.0838 -0.3261 +1305031472.5792 0.9528 -0.0402 1.2735 0.9001 0.2763 -0.0847 -0.3260 +1305031472.5892 0.9528 -0.0393 1.2742 0.9002 0.2759 -0.0851 -0.3261 +1305031472.5991 0.9528 -0.0384 1.2748 0.9003 0.2756 -0.0858 -0.3258 +1305031472.6094 0.9529 -0.0376 1.2754 0.9007 0.2752 -0.0859 -0.3250 +1305031472.6192 0.9530 -0.0366 1.2759 0.9007 0.2750 -0.0863 -0.3251 +1305031472.6291 0.9529 -0.0357 1.2765 0.9009 0.2747 -0.0867 -0.3247 +1305031472.6404 0.9528 -0.0348 1.2770 0.9010 0.2742 -0.0873 -0.3246 +1305031472.6492 0.9529 -0.0337 1.2776 0.9010 0.2740 -0.0875 -0.3248 +1305031472.6592 0.9531 -0.0327 1.2783 0.9010 0.2735 -0.0883 -0.3249 +1305031472.6694 0.9531 -0.0319 1.2789 0.9012 0.2733 -0.0889 -0.3245 +1305031472.6792 0.9530 -0.0308 1.2794 0.9008 0.2730 -0.0896 -0.3255 +1305031472.6892 0.9531 -0.0299 1.2801 0.9008 0.2730 -0.0898 -0.3254 +1305031472.6992 0.9531 -0.0289 1.2807 0.9005 0.2730 -0.0904 -0.3261 +1305031472.7091 0.9530 -0.0281 1.2812 0.9004 0.2729 -0.0909 -0.3264 +1305031472.7191 0.9529 -0.0270 1.2817 0.9000 0.2728 -0.0916 -0.3274 +1305031472.7292 0.9529 -0.0261 1.2823 0.8997 0.2732 -0.0916 -0.3280 +1305031472.7391 0.9529 -0.0251 1.2828 0.8995 0.2736 -0.0912 -0.3281 +1305031472.7492 0.9527 -0.0241 1.2832 0.8992 0.2737 -0.0914 -0.3289 +1305031472.7592 0.9525 -0.0233 1.2836 0.8990 0.2739 -0.0914 -0.3293 +1305031472.7692 0.9524 -0.0224 1.2840 0.8989 0.2744 -0.0908 -0.3294 +1305031472.7792 0.9521 -0.0216 1.2844 0.8985 0.2747 -0.0906 -0.3301 +1305031472.7892 0.9521 -0.0205 1.2848 0.8982 0.2747 -0.0900 -0.3311 +1305031472.7992 0.9518 -0.0196 1.2852 0.8978 0.2751 -0.0901 -0.3319 +1305031472.8092 0.9517 -0.0188 1.2857 0.8978 0.2747 -0.0900 -0.3322 +1305031472.8192 0.9515 -0.0181 1.2860 0.8979 0.2744 -0.0900 -0.3323 +1305031472.8292 0.9514 -0.0172 1.2864 0.8974 0.2742 -0.0904 -0.3336 +1305031472.8392 0.9512 -0.0163 1.2866 0.8970 0.2740 -0.0907 -0.3347 +1305031472.8492 0.9509 -0.0154 1.2870 0.8968 0.2742 -0.0914 -0.3349 +1305031472.8592 0.9508 -0.0148 1.2871 0.8973 0.2739 -0.0917 -0.3339 +1305031472.8691 0.9506 -0.0140 1.2872 0.8974 0.2735 -0.0922 -0.3338 +1305031472.8792 0.9505 -0.0133 1.2873 0.8976 0.2730 -0.0927 -0.3334 +1305031472.8892 0.9503 -0.0127 1.2874 0.8980 0.2725 -0.0932 -0.3327 +1305031472.8992 0.9500 -0.0121 1.2875 0.8982 0.2722 -0.0939 -0.3321 +1305031472.9092 0.9498 -0.0114 1.2876 0.8984 0.2719 -0.0942 -0.3318 +1305031472.9192 0.9496 -0.0107 1.2876 0.8985 0.2714 -0.0946 -0.3317 +1305031472.9291 0.9495 -0.0102 1.2876 0.8985 0.2711 -0.0950 -0.3318 +1305031472.9393 0.9494 -0.0097 1.2876 0.8986 0.2708 -0.0952 -0.3318 +1305031472.9492 0.9492 -0.0093 1.2876 0.8987 0.2703 -0.0951 -0.3320 +1305031472.9591 0.9490 -0.0089 1.2876 0.8989 0.2701 -0.0952 -0.3315 +1305031472.9691 0.9489 -0.0084 1.2876 0.8992 0.2700 -0.0953 -0.3309 +1305031472.9792 0.9487 -0.0080 1.2874 0.8991 0.2700 -0.0956 -0.3309 +1305031472.9892 0.9484 -0.0076 1.2873 0.8991 0.2701 -0.0960 -0.3309 +1305031472.9991 0.9483 -0.0074 1.2872 0.8992 0.2703 -0.0962 -0.3302 +1305031473.0092 0.9481 -0.0071 1.2871 0.8993 0.2705 -0.0966 -0.3298 +1305031473.0192 0.9478 -0.0068 1.2871 0.8993 0.2707 -0.0969 -0.3295 +1305031473.0292 0.9477 -0.0067 1.2870 0.8994 0.2709 -0.0969 -0.3290 +1305031473.0393 0.9475 -0.0064 1.2870 0.8994 0.2712 -0.0969 -0.3290 +1305031473.0492 0.9473 -0.0061 1.2870 0.8993 0.2716 -0.0968 -0.3290 +1305031473.0592 0.9471 -0.0060 1.2870 0.8992 0.2719 -0.0965 -0.3289 +1305031473.0692 0.9469 -0.0058 1.2870 0.8991 0.2721 -0.0961 -0.3292 +1305031473.0792 0.9468 -0.0056 1.2871 0.8989 0.2725 -0.0955 -0.3295 +1305031473.0892 0.9466 -0.0054 1.2872 0.8988 0.2728 -0.0949 -0.3298 +1305031473.0991 0.9465 -0.0051 1.2872 0.8988 0.2732 -0.0942 -0.3296 +1305031473.1092 0.9463 -0.0049 1.2872 0.8987 0.2735 -0.0937 -0.3298 +1305031473.1192 0.9460 -0.0049 1.2873 0.8987 0.2739 -0.0933 -0.3296 +1305031473.1291 0.9459 -0.0047 1.2874 0.8985 0.2739 -0.0933 -0.3302 +1305031473.1392 0.9457 -0.0046 1.2876 0.8982 0.2740 -0.0937 -0.3306 +1305031473.1492 0.9456 -0.0044 1.2877 0.8980 0.2742 -0.0942 -0.3309 +1305031473.1592 0.9455 -0.0043 1.2879 0.8979 0.2743 -0.0947 -0.3310 +1305031473.1691 0.9454 -0.0042 1.2882 0.8978 0.2745 -0.0950 -0.3311 +1305031473.1792 0.9455 -0.0040 1.2883 0.8980 0.2745 -0.0949 -0.3305 +1305031473.1892 0.9454 -0.0038 1.2886 0.8977 0.2744 -0.0951 -0.3313 +1305031473.1991 0.9453 -0.0038 1.2888 0.8978 0.2746 -0.0950 -0.3310 diff --git a/vSLAM/ch8/data/rgb.txt b/vSLAM/ch8/data/rgb.txt new file mode 100644 index 00000000..1f7a37b3 --- /dev/null +++ b/vSLAM/ch8/data/rgb.txt @@ -0,0 +1,616 @@ +# color images +# file: 'rgbd_dataset_freiburg1_desk.bag' +# timestamp filename +1305031452.791720 rgb/1305031452.791720.png +1305031452.823674 rgb/1305031452.823674.png +1305031452.859642 rgb/1305031452.859642.png +1305031452.891726 rgb/1305031452.891726.png +1305031452.923715 rgb/1305031452.923715.png +1305031452.959701 rgb/1305031452.959701.png +1305031452.991647 rgb/1305031452.991647.png +1305031453.023650 rgb/1305031453.023650.png +1305031453.059754 rgb/1305031453.059754.png +1305031453.091704 rgb/1305031453.091704.png +1305031453.123633 rgb/1305031453.123633.png +1305031453.159673 rgb/1305031453.159673.png +1305031453.191726 rgb/1305031453.191726.png +1305031453.223689 rgb/1305031453.223689.png +1305031453.259670 rgb/1305031453.259670.png +1305031453.291696 rgb/1305031453.291696.png +1305031453.323682 rgb/1305031453.323682.png +1305031453.359684 rgb/1305031453.359684.png +1305031453.391690 rgb/1305031453.391690.png +1305031453.423683 rgb/1305031453.423683.png +1305031453.459685 rgb/1305031453.459685.png +1305031453.491698 rgb/1305031453.491698.png +1305031453.523684 rgb/1305031453.523684.png +1305031453.559753 rgb/1305031453.559753.png +1305031453.591640 rgb/1305031453.591640.png +1305031453.627706 rgb/1305031453.627706.png +1305031453.659600 rgb/1305031453.659600.png +1305031453.691678 rgb/1305031453.691678.png +1305031453.727652 rgb/1305031453.727652.png +1305031453.759694 rgb/1305031453.759694.png +1305031453.791716 rgb/1305031453.791716.png +1305031453.827773 rgb/1305031453.827773.png +1305031453.859705 rgb/1305031453.859705.png +1305031453.891710 rgb/1305031453.891710.png +1305031453.927723 rgb/1305031453.927723.png +1305031453.959641 rgb/1305031453.959641.png +1305031453.991624 rgb/1305031453.991624.png +1305031454.027662 rgb/1305031454.027662.png +1305031454.059654 rgb/1305031454.059654.png +1305031454.091651 rgb/1305031454.091651.png +1305031454.127701 rgb/1305031454.127701.png +1305031454.159672 rgb/1305031454.159672.png +1305031454.191658 rgb/1305031454.191658.png +1305031454.227671 rgb/1305031454.227671.png +1305031454.259627 rgb/1305031454.259627.png +1305031454.291639 rgb/1305031454.291639.png +1305031454.327699 rgb/1305031454.327699.png +1305031454.359636 rgb/1305031454.359636.png +1305031454.391677 rgb/1305031454.391677.png +1305031454.427465 rgb/1305031454.427465.png +1305031454.459913 rgb/1305031454.459913.png +1305031454.491617 rgb/1305031454.491617.png +1305031454.527700 rgb/1305031454.527700.png +1305031454.559575 rgb/1305031454.559575.png +1305031454.591635 rgb/1305031454.591635.png +1305031454.627580 rgb/1305031454.627580.png +1305031454.659528 rgb/1305031454.659528.png +1305031454.691884 rgb/1305031454.691884.png +1305031454.727659 rgb/1305031454.727659.png +1305031454.759732 rgb/1305031454.759732.png +1305031454.791641 rgb/1305031454.791641.png +1305031454.827570 rgb/1305031454.827570.png +1305031454.859620 rgb/1305031454.859620.png +1305031454.891764 rgb/1305031454.891764.png +1305031454.927567 rgb/1305031454.927567.png +1305031454.959648 rgb/1305031454.959648.png +1305031454.991937 rgb/1305031454.991937.png +1305031455.027799 rgb/1305031455.027799.png +1305031455.059636 rgb/1305031455.059636.png +1305031455.091700 rgb/1305031455.091700.png +1305031455.127695 rgb/1305031455.127695.png +1305031455.159720 rgb/1305031455.159720.png +1305031455.191655 rgb/1305031455.191655.png +1305031455.227581 rgb/1305031455.227581.png +1305031455.259631 rgb/1305031455.259631.png +1305031455.291831 rgb/1305031455.291831.png +1305031455.327766 rgb/1305031455.327766.png +1305031455.359630 rgb/1305031455.359630.png +1305031455.391665 rgb/1305031455.391665.png +1305031455.427642 rgb/1305031455.427642.png +1305031455.459589 rgb/1305031455.459589.png +1305031455.491637 rgb/1305031455.491637.png +1305031455.527610 rgb/1305031455.527610.png +1305031455.559669 rgb/1305031455.559669.png +1305031455.591645 rgb/1305031455.591645.png +1305031455.627617 rgb/1305031455.627617.png +1305031455.659615 rgb/1305031455.659615.png +1305031455.691605 rgb/1305031455.691605.png +1305031455.727628 rgb/1305031455.727628.png +1305031455.759683 rgb/1305031455.759683.png +1305031455.791666 rgb/1305031455.791666.png +1305031455.827590 rgb/1305031455.827590.png +1305031455.859526 rgb/1305031455.859526.png +1305031455.891657 rgb/1305031455.891657.png +1305031455.927955 rgb/1305031455.927955.png +1305031455.959716 rgb/1305031455.959716.png +1305031455.991694 rgb/1305031455.991694.png +1305031456.027770 rgb/1305031456.027770.png +1305031456.059713 rgb/1305031456.059713.png +1305031456.091707 rgb/1305031456.091707.png +1305031456.127645 rgb/1305031456.127645.png +1305031456.159731 rgb/1305031456.159731.png +1305031456.191658 rgb/1305031456.191658.png +1305031456.227678 rgb/1305031456.227678.png +1305031456.259614 rgb/1305031456.259614.png +1305031456.291675 rgb/1305031456.291675.png +1305031456.327718 rgb/1305031456.327718.png +1305031456.359846 rgb/1305031456.359846.png +1305031456.391619 rgb/1305031456.391619.png +1305031456.427662 rgb/1305031456.427662.png +1305031456.459610 rgb/1305031456.459610.png +1305031456.491677 rgb/1305031456.491677.png +1305031456.527641 rgb/1305031456.527641.png +1305031456.559608 rgb/1305031456.559608.png +1305031456.591651 rgb/1305031456.591651.png +1305031456.627612 rgb/1305031456.627612.png +1305031456.659665 rgb/1305031456.659665.png +1305031456.691612 rgb/1305031456.691612.png +1305031456.727693 rgb/1305031456.727693.png +1305031456.759615 rgb/1305031456.759615.png +1305031456.791649 rgb/1305031456.791649.png +1305031456.827603 rgb/1305031456.827603.png +1305031456.859634 rgb/1305031456.859634.png +1305031456.891672 rgb/1305031456.891672.png +1305031456.927690 rgb/1305031456.927690.png +1305031456.959667 rgb/1305031456.959667.png +1305031456.991709 rgb/1305031456.991709.png +1305031457.027648 rgb/1305031457.027648.png +1305031457.059621 rgb/1305031457.059621.png +1305031457.091655 rgb/1305031457.091655.png +1305031457.127632 rgb/1305031457.127632.png +1305031457.159693 rgb/1305031457.159693.png +1305031457.191735 rgb/1305031457.191735.png +1305031457.227543 rgb/1305031457.227543.png +1305031457.259691 rgb/1305031457.259691.png +1305031457.291656 rgb/1305031457.291656.png +1305031457.327548 rgb/1305031457.327548.png +1305031457.359712 rgb/1305031457.359712.png +1305031457.391684 rgb/1305031457.391684.png +1305031457.427641 rgb/1305031457.427641.png +1305031457.459614 rgb/1305031457.459614.png +1305031457.491705 rgb/1305031457.491705.png +1305031457.527638 rgb/1305031457.527638.png +1305031457.559685 rgb/1305031457.559685.png +1305031457.591678 rgb/1305031457.591678.png +1305031457.627526 rgb/1305031457.627526.png +1305031457.659632 rgb/1305031457.659632.png +1305031457.691570 rgb/1305031457.691570.png +1305031457.727669 rgb/1305031457.727669.png +1305031457.759556 rgb/1305031457.759556.png +1305031457.791567 rgb/1305031457.791567.png +1305031457.827699 rgb/1305031457.827699.png +1305031457.859623 rgb/1305031457.859623.png +1305031457.891593 rgb/1305031457.891593.png +1305031457.927633 rgb/1305031457.927633.png +1305031457.959632 rgb/1305031457.959632.png +1305031457.991644 rgb/1305031457.991644.png +1305031458.027845 rgb/1305031458.027845.png +1305031458.059689 rgb/1305031458.059689.png +1305031458.091690 rgb/1305031458.091690.png +1305031458.127605 rgb/1305031458.127605.png +1305031458.159638 rgb/1305031458.159638.png +1305031458.191646 rgb/1305031458.191646.png +1305031458.227611 rgb/1305031458.227611.png +1305031458.259934 rgb/1305031458.259934.png +1305031458.291664 rgb/1305031458.291664.png +1305031458.327628 rgb/1305031458.327628.png +1305031458.359590 rgb/1305031458.359590.png +1305031458.391626 rgb/1305031458.391626.png +1305031458.427598 rgb/1305031458.427598.png +1305031458.459637 rgb/1305031458.459637.png +1305031458.491696 rgb/1305031458.491696.png +1305031458.527737 rgb/1305031458.527737.png +1305031458.559628 rgb/1305031458.559628.png +1305031458.591641 rgb/1305031458.591641.png +1305031458.627659 rgb/1305031458.627659.png +1305031458.659623 rgb/1305031458.659623.png +1305031458.691674 rgb/1305031458.691674.png +1305031458.727650 rgb/1305031458.727650.png +1305031458.759945 rgb/1305031458.759945.png +1305031458.791632 rgb/1305031458.791632.png +1305031458.827564 rgb/1305031458.827564.png +1305031458.859887 rgb/1305031458.859887.png +1305031458.891665 rgb/1305031458.891665.png +1305031458.927621 rgb/1305031458.927621.png +1305031458.959617 rgb/1305031458.959617.png +1305031458.991647 rgb/1305031458.991647.png +1305031459.027665 rgb/1305031459.027665.png +1305031459.059631 rgb/1305031459.059631.png +1305031459.091650 rgb/1305031459.091650.png +1305031459.127618 rgb/1305031459.127618.png +1305031459.159639 rgb/1305031459.159639.png +1305031459.191674 rgb/1305031459.191674.png +1305031459.227607 rgb/1305031459.227607.png +1305031459.259760 rgb/1305031459.259760.png +1305031459.291690 rgb/1305031459.291690.png +1305031459.327632 rgb/1305031459.327632.png +1305031459.359651 rgb/1305031459.359651.png +1305031459.391667 rgb/1305031459.391667.png +1305031459.427646 rgb/1305031459.427646.png +1305031459.459679 rgb/1305031459.459679.png +1305031459.491555 rgb/1305031459.491555.png +1305031459.527594 rgb/1305031459.527594.png +1305031459.559647 rgb/1305031459.559647.png +1305031459.591695 rgb/1305031459.591695.png +1305031459.627608 rgb/1305031459.627608.png +1305031459.659641 rgb/1305031459.659641.png +1305031459.691604 rgb/1305031459.691604.png +1305031459.727551 rgb/1305031459.727551.png +1305031459.759635 rgb/1305031459.759635.png +1305031459.791650 rgb/1305031459.791650.png +1305031459.827664 rgb/1305031459.827664.png +1305031459.859660 rgb/1305031459.859660.png +1305031459.891596 rgb/1305031459.891596.png +1305031459.927607 rgb/1305031459.927607.png +1305031459.959650 rgb/1305031459.959650.png +1305031459.991725 rgb/1305031459.991725.png +1305031460.027565 rgb/1305031460.027565.png +1305031460.059659 rgb/1305031460.059659.png +1305031460.091717 rgb/1305031460.091717.png +1305031460.127690 rgb/1305031460.127690.png +1305031460.159678 rgb/1305031460.159678.png +1305031460.191559 rgb/1305031460.191559.png +1305031460.227761 rgb/1305031460.227761.png +1305031460.259667 rgb/1305031460.259667.png +1305031460.291689 rgb/1305031460.291689.png +1305031460.327512 rgb/1305031460.327512.png +1305031460.359630 rgb/1305031460.359630.png +1305031460.391611 rgb/1305031460.391611.png +1305031460.427477 rgb/1305031460.427477.png +1305031460.459620 rgb/1305031460.459620.png +1305031460.491504 rgb/1305031460.491504.png +1305031460.527570 rgb/1305031460.527570.png +1305031460.559647 rgb/1305031460.559647.png +1305031460.591855 rgb/1305031460.591855.png +1305031460.627625 rgb/1305031460.627625.png +1305031460.659764 rgb/1305031460.659764.png +1305031460.691671 rgb/1305031460.691671.png +1305031460.727675 rgb/1305031460.727675.png +1305031460.759667 rgb/1305031460.759667.png +1305031460.791660 rgb/1305031460.791660.png +1305031460.827660 rgb/1305031460.827660.png +1305031460.859714 rgb/1305031460.859714.png +1305031460.891774 rgb/1305031460.891774.png +1305031460.927562 rgb/1305031460.927562.png +1305031460.959649 rgb/1305031460.959649.png +1305031460.991668 rgb/1305031460.991668.png +1305031461.027620 rgb/1305031461.027620.png +1305031461.059662 rgb/1305031461.059662.png +1305031461.091728 rgb/1305031461.091728.png +1305031461.127586 rgb/1305031461.127586.png +1305031461.159720 rgb/1305031461.159720.png +1305031461.192013 rgb/1305031461.192013.png +1305031461.227607 rgb/1305031461.227607.png +1305031461.259642 rgb/1305031461.259642.png +1305031461.291656 rgb/1305031461.291656.png +1305031461.327751 rgb/1305031461.327751.png +1305031461.359709 rgb/1305031461.359709.png +1305031461.391708 rgb/1305031461.391708.png +1305031461.427624 rgb/1305031461.427624.png +1305031461.459781 rgb/1305031461.459781.png +1305031461.491677 rgb/1305031461.491677.png +1305031461.527705 rgb/1305031461.527705.png +1305031461.559677 rgb/1305031461.559677.png +1305031461.591690 rgb/1305031461.591690.png +1305031461.627541 rgb/1305031461.627541.png +1305031461.659622 rgb/1305031461.659622.png +1305031461.691563 rgb/1305031461.691563.png +1305031461.727602 rgb/1305031461.727602.png +1305031461.759684 rgb/1305031461.759684.png +1305031461.791612 rgb/1305031461.791612.png +1305031461.827615 rgb/1305031461.827615.png +1305031461.859767 rgb/1305031461.859767.png +1305031461.891723 rgb/1305031461.891723.png +1305031461.927758 rgb/1305031461.927758.png +1305031461.959703 rgb/1305031461.959703.png +1305031461.991590 rgb/1305031461.991590.png +1305031462.027675 rgb/1305031462.027675.png +1305031462.059837 rgb/1305031462.059837.png +1305031462.091777 rgb/1305031462.091777.png +1305031462.127739 rgb/1305031462.127739.png +1305031462.159646 rgb/1305031462.159646.png +1305031462.191641 rgb/1305031462.191641.png +1305031462.227633 rgb/1305031462.227633.png +1305031462.259765 rgb/1305031462.259765.png +1305031462.291629 rgb/1305031462.291629.png +1305031462.327540 rgb/1305031462.327540.png +1305031462.359732 rgb/1305031462.359732.png +1305031462.391695 rgb/1305031462.391695.png +1305031462.427635 rgb/1305031462.427635.png +1305031462.459897 rgb/1305031462.459897.png +1305031462.492008 rgb/1305031462.492008.png +1305031462.527670 rgb/1305031462.527670.png +1305031462.559862 rgb/1305031462.559862.png +1305031462.591862 rgb/1305031462.591862.png +1305031462.627851 rgb/1305031462.627851.png +1305031462.659660 rgb/1305031462.659660.png +1305031462.692548 rgb/1305031462.692548.png +1305031462.727652 rgb/1305031462.727652.png +1305031462.759782 rgb/1305031462.759782.png +1305031462.791943 rgb/1305031462.791943.png +1305031462.827816 rgb/1305031462.827816.png +1305031462.859782 rgb/1305031462.859782.png +1305031462.891847 rgb/1305031462.891847.png +1305031462.927607 rgb/1305031462.927607.png +1305031462.959676 rgb/1305031462.959676.png +1305031462.995550 rgb/1305031462.995550.png +1305031463.027667 rgb/1305031463.027667.png +1305031463.059810 rgb/1305031463.059810.png +1305031463.095809 rgb/1305031463.095809.png +1305031463.127550 rgb/1305031463.127550.png +1305031463.159787 rgb/1305031463.159787.png +1305031463.195657 rgb/1305031463.195657.png +1305031463.227784 rgb/1305031463.227784.png +1305031463.260034 rgb/1305031463.260034.png +1305031463.295737 rgb/1305031463.295737.png +1305031463.327739 rgb/1305031463.327739.png +1305031463.359750 rgb/1305031463.359750.png +1305031463.395630 rgb/1305031463.395630.png +1305031463.427716 rgb/1305031463.427716.png +1305031463.459756 rgb/1305031463.459756.png +1305031463.495629 rgb/1305031463.495629.png +1305031463.527670 rgb/1305031463.527670.png +1305031463.559751 rgb/1305031463.559751.png +1305031463.595600 rgb/1305031463.595600.png +1305031463.627588 rgb/1305031463.627588.png +1305031463.659766 rgb/1305031463.659766.png +1305031463.695640 rgb/1305031463.695640.png +1305031463.727588 rgb/1305031463.727588.png +1305031463.759674 rgb/1305031463.759674.png +1305031463.795647 rgb/1305031463.795647.png +1305031463.827761 rgb/1305031463.827761.png +1305031463.859910 rgb/1305031463.859910.png +1305031463.895648 rgb/1305031463.895648.png +1305031463.927664 rgb/1305031463.927664.png +1305031463.959680 rgb/1305031463.959680.png +1305031463.995821 rgb/1305031463.995821.png +1305031464.027703 rgb/1305031464.027703.png +1305031464.059652 rgb/1305031464.059652.png +1305031464.095634 rgb/1305031464.095634.png +1305031464.127681 rgb/1305031464.127681.png +1305031464.159817 rgb/1305031464.159817.png +1305031464.195585 rgb/1305031464.195585.png +1305031464.227624 rgb/1305031464.227624.png +1305031464.259644 rgb/1305031464.259644.png +1305031464.295667 rgb/1305031464.295667.png +1305031464.327866 rgb/1305031464.327866.png +1305031464.359684 rgb/1305031464.359684.png +1305031464.395611 rgb/1305031464.395611.png +1305031464.427634 rgb/1305031464.427634.png +1305031464.459689 rgb/1305031464.459689.png +1305031464.495633 rgb/1305031464.495633.png +1305031464.527574 rgb/1305031464.527574.png +1305031464.559703 rgb/1305031464.559703.png +1305031464.595698 rgb/1305031464.595698.png +1305031464.627672 rgb/1305031464.627672.png +1305031464.659749 rgb/1305031464.659749.png +1305031464.695663 rgb/1305031464.695663.png +1305031464.727652 rgb/1305031464.727652.png +1305031464.759740 rgb/1305031464.759740.png +1305031464.796021 rgb/1305031464.796021.png +1305031464.827759 rgb/1305031464.827759.png +1305031464.859654 rgb/1305031464.859654.png +1305031464.895817 rgb/1305031464.895817.png +1305031464.927799 rgb/1305031464.927799.png +1305031464.959763 rgb/1305031464.959763.png +1305031464.995687 rgb/1305031464.995687.png +1305031465.027823 rgb/1305031465.027823.png +1305031465.059749 rgb/1305031465.059749.png +1305031465.095700 rgb/1305031465.095700.png +1305031465.127664 rgb/1305031465.127664.png +1305031465.159842 rgb/1305031465.159842.png +1305031465.195564 rgb/1305031465.195564.png +1305031465.227907 rgb/1305031465.227907.png +1305031465.259807 rgb/1305031465.259807.png +1305031465.295623 rgb/1305031465.295623.png +1305031465.327674 rgb/1305031465.327674.png +1305031465.359948 rgb/1305031465.359948.png +1305031465.395586 rgb/1305031465.395586.png +1305031465.427697 rgb/1305031465.427697.png +1305031465.460125 rgb/1305031465.460125.png +1305031465.495703 rgb/1305031465.495703.png +1305031465.527622 rgb/1305031465.527622.png +1305031465.559812 rgb/1305031465.559812.png +1305031465.595599 rgb/1305031465.595599.png +1305031465.627688 rgb/1305031465.627688.png +1305031465.660060 rgb/1305031465.660060.png +1305031465.695668 rgb/1305031465.695668.png +1305031465.727682 rgb/1305031465.727682.png +1305031465.759766 rgb/1305031465.759766.png +1305031465.795937 rgb/1305031465.795937.png +1305031465.827996 rgb/1305031465.827996.png +1305031465.859861 rgb/1305031465.859861.png +1305031465.895494 rgb/1305031465.895494.png +1305031465.927495 rgb/1305031465.927495.png +1305031465.959710 rgb/1305031465.959710.png +1305031465.995753 rgb/1305031465.995753.png +1305031466.027644 rgb/1305031466.027644.png +1305031466.059757 rgb/1305031466.059757.png +1305031466.095840 rgb/1305031466.095840.png +1305031466.127640 rgb/1305031466.127640.png +1305031466.160428 rgb/1305031466.160428.png +1305031466.195833 rgb/1305031466.195833.png +1305031466.227951 rgb/1305031466.227951.png +1305031466.259815 rgb/1305031466.259815.png +1305031466.295737 rgb/1305031466.295737.png +1305031466.327702 rgb/1305031466.327702.png +1305031466.359829 rgb/1305031466.359829.png +1305031466.395784 rgb/1305031466.395784.png +1305031466.427819 rgb/1305031466.427819.png +1305031466.459790 rgb/1305031466.459790.png +1305031466.495809 rgb/1305031466.495809.png +1305031466.527538 rgb/1305031466.527538.png +1305031466.560353 rgb/1305031466.560353.png +1305031466.595936 rgb/1305031466.595936.png +1305031466.627549 rgb/1305031466.627549.png +1305031466.659688 rgb/1305031466.659688.png +1305031466.695822 rgb/1305031466.695822.png +1305031466.728074 rgb/1305031466.728074.png +1305031466.759637 rgb/1305031466.759637.png +1305031466.795604 rgb/1305031466.795604.png +1305031466.827879 rgb/1305031466.827879.png +1305031466.859665 rgb/1305031466.859665.png +1305031466.895694 rgb/1305031466.895694.png +1305031466.927756 rgb/1305031466.927756.png +1305031466.959728 rgb/1305031466.959728.png +1305031466.995712 rgb/1305031466.995712.png +1305031467.027843 rgb/1305031467.027843.png +1305031467.059700 rgb/1305031467.059700.png +1305031467.095687 rgb/1305031467.095687.png +1305031467.128974 rgb/1305031467.128974.png +1305031467.159660 rgb/1305031467.159660.png +1305031467.195663 rgb/1305031467.195663.png +1305031467.227704 rgb/1305031467.227704.png +1305031467.259694 rgb/1305031467.259694.png +1305031467.295846 rgb/1305031467.295846.png +1305031467.328008 rgb/1305031467.328008.png +1305031467.359654 rgb/1305031467.359654.png +1305031467.395756 rgb/1305031467.395756.png +1305031467.427783 rgb/1305031467.427783.png +1305031467.459692 rgb/1305031467.459692.png +1305031467.496058 rgb/1305031467.496058.png +1305031467.527663 rgb/1305031467.527663.png +1305031467.559763 rgb/1305031467.559763.png +1305031467.595989 rgb/1305031467.595989.png +1305031467.627532 rgb/1305031467.627532.png +1305031467.659626 rgb/1305031467.659626.png +1305031467.695886 rgb/1305031467.695886.png +1305031467.727535 rgb/1305031467.727535.png +1305031467.759907 rgb/1305031467.759907.png +1305031467.796075 rgb/1305031467.796075.png +1305031467.827800 rgb/1305031467.827800.png +1305031467.859729 rgb/1305031467.859729.png +1305031467.895947 rgb/1305031467.895947.png +1305031467.927754 rgb/1305031467.927754.png +1305031467.959826 rgb/1305031467.959826.png +1305031467.995754 rgb/1305031467.995754.png +1305031468.028107 rgb/1305031468.028107.png +1305031468.059850 rgb/1305031468.059850.png +1305031468.095867 rgb/1305031468.095867.png +1305031468.127816 rgb/1305031468.127816.png +1305031468.159864 rgb/1305031468.159864.png +1305031468.195985 rgb/1305031468.195985.png +1305031468.228158 rgb/1305031468.228158.png +1305031468.259754 rgb/1305031468.259754.png +1305031468.295830 rgb/1305031468.295830.png +1305031468.327847 rgb/1305031468.327847.png +1305031468.359787 rgb/1305031468.359787.png +1305031468.395860 rgb/1305031468.395860.png +1305031468.428025 rgb/1305031468.428025.png +1305031468.459759 rgb/1305031468.459759.png +1305031468.495809 rgb/1305031468.495809.png +1305031468.527756 rgb/1305031468.527756.png +1305031468.559739 rgb/1305031468.559739.png +1305031468.595768 rgb/1305031468.595768.png +1305031468.627626 rgb/1305031468.627626.png +1305031468.659579 rgb/1305031468.659579.png +1305031468.695835 rgb/1305031468.695835.png +1305031468.727785 rgb/1305031468.727785.png +1305031468.759628 rgb/1305031468.759628.png +1305031468.795796 rgb/1305031468.795796.png +1305031468.829247 rgb/1305031468.829247.png +1305031468.859659 rgb/1305031468.859659.png +1305031468.895873 rgb/1305031468.895873.png +1305031468.928141 rgb/1305031468.928141.png +1305031468.959594 rgb/1305031468.959594.png +1305031468.995711 rgb/1305031468.995711.png +1305031469.027699 rgb/1305031469.027699.png +1305031469.059832 rgb/1305031469.059832.png +1305031469.095723 rgb/1305031469.095723.png +1305031469.127679 rgb/1305031469.127679.png +1305031469.159703 rgb/1305031469.159703.png +1305031469.195540 rgb/1305031469.195540.png +1305031469.227754 rgb/1305031469.227754.png +1305031469.259586 rgb/1305031469.259586.png +1305031469.296754 rgb/1305031469.296754.png +1305031469.327618 rgb/1305031469.327618.png +1305031469.359592 rgb/1305031469.359592.png +1305031469.395695 rgb/1305031469.395695.png +1305031469.427651 rgb/1305031469.427651.png +1305031469.459668 rgb/1305031469.459668.png +1305031469.495744 rgb/1305031469.495744.png +1305031469.527622 rgb/1305031469.527622.png +1305031469.559645 rgb/1305031469.559645.png +1305031469.595755 rgb/1305031469.595755.png +1305031469.627752 rgb/1305031469.627752.png +1305031469.659590 rgb/1305031469.659590.png +1305031469.695613 rgb/1305031469.695613.png +1305031469.727679 rgb/1305031469.727679.png +1305031469.759599 rgb/1305031469.759599.png +1305031469.795621 rgb/1305031469.795621.png +1305031469.827526 rgb/1305031469.827526.png +1305031469.859574 rgb/1305031469.859574.png +1305031469.895755 rgb/1305031469.895755.png +1305031469.927854 rgb/1305031469.927854.png +1305031469.959805 rgb/1305031469.959805.png +1305031469.995551 rgb/1305031469.995551.png +1305031470.027694 rgb/1305031470.027694.png +1305031470.059638 rgb/1305031470.059638.png +1305031470.095944 rgb/1305031470.095944.png +1305031470.127633 rgb/1305031470.127633.png +1305031470.159626 rgb/1305031470.159626.png +1305031470.196092 rgb/1305031470.196092.png +1305031470.227618 rgb/1305031470.227618.png +1305031470.259965 rgb/1305031470.259965.png +1305031470.295718 rgb/1305031470.295718.png +1305031470.327644 rgb/1305031470.327644.png +1305031470.359624 rgb/1305031470.359624.png +1305031470.395823 rgb/1305031470.395823.png +1305031470.427641 rgb/1305031470.427641.png +1305031470.459721 rgb/1305031470.459721.png +1305031470.495686 rgb/1305031470.495686.png +1305031470.527689 rgb/1305031470.527689.png +1305031470.559677 rgb/1305031470.559677.png +1305031470.595760 rgb/1305031470.595760.png +1305031470.627729 rgb/1305031470.627729.png +1305031470.659690 rgb/1305031470.659690.png +1305031470.695630 rgb/1305031470.695630.png +1305031470.727654 rgb/1305031470.727654.png +1305031470.759682 rgb/1305031470.759682.png +1305031470.795615 rgb/1305031470.795615.png +1305031470.827831 rgb/1305031470.827831.png +1305031470.859645 rgb/1305031470.859645.png +1305031470.895722 rgb/1305031470.895722.png +1305031470.927684 rgb/1305031470.927684.png +1305031470.959647 rgb/1305031470.959647.png +1305031470.995996 rgb/1305031470.995996.png +1305031471.027644 rgb/1305031471.027644.png +1305031471.059636 rgb/1305031471.059636.png +1305031471.095777 rgb/1305031471.095777.png +1305031471.127663 rgb/1305031471.127663.png +1305031471.159649 rgb/1305031471.159649.png +1305031471.195703 rgb/1305031471.195703.png +1305031471.227569 rgb/1305031471.227569.png +1305031471.259722 rgb/1305031471.259722.png +1305031471.296068 rgb/1305031471.296068.png +1305031471.327642 rgb/1305031471.327642.png +1305031471.359615 rgb/1305031471.359615.png +1305031471.395730 rgb/1305031471.395730.png +1305031471.427704 rgb/1305031471.427704.png +1305031471.459647 rgb/1305031471.459647.png +1305031471.496491 rgb/1305031471.496491.png +1305031471.527624 rgb/1305031471.527624.png +1305031471.559671 rgb/1305031471.559671.png +1305031471.595702 rgb/1305031471.595702.png +1305031471.627621 rgb/1305031471.627621.png +1305031471.659642 rgb/1305031471.659642.png +1305031471.695609 rgb/1305031471.695609.png +1305031471.727501 rgb/1305031471.727501.png +1305031471.759702 rgb/1305031471.759702.png +1305031471.795801 rgb/1305031471.795801.png +1305031471.827639 rgb/1305031471.827639.png +1305031471.859665 rgb/1305031471.859665.png +1305031471.895604 rgb/1305031471.895604.png +1305031471.927651 rgb/1305031471.927651.png +1305031471.959643 rgb/1305031471.959643.png +1305031471.995573 rgb/1305031471.995573.png +1305031472.027638 rgb/1305031472.027638.png +1305031472.059668 rgb/1305031472.059668.png +1305031472.095601 rgb/1305031472.095601.png +1305031472.127594 rgb/1305031472.127594.png +1305031472.159645 rgb/1305031472.159645.png +1305031472.195682 rgb/1305031472.195682.png +1305031472.227626 rgb/1305031472.227626.png +1305031472.263840 rgb/1305031472.263840.png +1305031472.295671 rgb/1305031472.295671.png +1305031472.327678 rgb/1305031472.327678.png +1305031472.363577 rgb/1305031472.363577.png +1305031472.395599 rgb/1305031472.395599.png +1305031472.427686 rgb/1305031472.427686.png +1305031472.463603 rgb/1305031472.463603.png +1305031472.495626 rgb/1305031472.495626.png +1305031472.527625 rgb/1305031472.527625.png +1305031472.563587 rgb/1305031472.563587.png +1305031472.595675 rgb/1305031472.595675.png +1305031472.627701 rgb/1305031472.627701.png +1305031472.663575 rgb/1305031472.663575.png +1305031472.695755 rgb/1305031472.695755.png +1305031472.727628 rgb/1305031472.727628.png +1305031472.763578 rgb/1305031472.763578.png +1305031472.795640 rgb/1305031472.795640.png +1305031472.827627 rgb/1305031472.827627.png +1305031472.863598 rgb/1305031472.863598.png +1305031472.895713 rgb/1305031472.895713.png +1305031472.927685 rgb/1305031472.927685.png +1305031472.963756 rgb/1305031472.963756.png +1305031472.995704 rgb/1305031472.995704.png +1305031473.027638 rgb/1305031473.027638.png +1305031473.063684 rgb/1305031473.063684.png +1305031473.095695 rgb/1305031473.095695.png +1305031473.127744 rgb/1305031473.127744.png +1305031473.167060 rgb/1305031473.167060.png +1305031473.196069 rgb/1305031473.196069.png diff --git a/vSLAM/ch8/data/rgb/1305031453.359684.png b/vSLAM/ch8/data/rgb/1305031453.359684.png new file mode 100644 index 00000000..fcfeae1b Binary files /dev/null and b/vSLAM/ch8/data/rgb/1305031453.359684.png differ diff --git a/vSLAM/ch8/data/rgb/1305031453.391690.png b/vSLAM/ch8/data/rgb/1305031453.391690.png new file mode 100644 index 00000000..f7773244 Binary files /dev/null and b/vSLAM/ch8/data/rgb/1305031453.391690.png differ diff --git a/vSLAM/ch8/data/rgb/1305031453.423683.png b/vSLAM/ch8/data/rgb/1305031453.423683.png new file mode 100644 index 00000000..1c2fc096 Binary files /dev/null and b/vSLAM/ch8/data/rgb/1305031453.423683.png differ diff --git a/vSLAM/ch8/data/rgb/1305031453.459685.png b/vSLAM/ch8/data/rgb/1305031453.459685.png new file mode 100644 index 00000000..660d4dfe Binary files /dev/null and b/vSLAM/ch8/data/rgb/1305031453.459685.png differ diff --git a/vSLAM/ch8/data/rgb/1305031453.491698.png b/vSLAM/ch8/data/rgb/1305031453.491698.png new file mode 100644 index 00000000..a8e8faf1 Binary files /dev/null and b/vSLAM/ch8/data/rgb/1305031453.491698.png differ diff --git a/vSLAM/ch8/data/rgb/1305031453.523684.png b/vSLAM/ch8/data/rgb/1305031453.523684.png new file mode 100644 index 00000000..525b31e6 Binary files /dev/null and b/vSLAM/ch8/data/rgb/1305031453.523684.png differ diff --git a/vSLAM/ch8/data/rgb/1305031453.559753.png b/vSLAM/ch8/data/rgb/1305031453.559753.png new file mode 100644 index 00000000..afb28d21 Binary files /dev/null and b/vSLAM/ch8/data/rgb/1305031453.559753.png differ diff --git a/vSLAM/ch8/data/rgb/1305031453.591640.png b/vSLAM/ch8/data/rgb/1305031453.591640.png new file mode 100644 index 00000000..ab748aa5 Binary files /dev/null and b/vSLAM/ch8/data/rgb/1305031453.591640.png differ diff --git a/vSLAM/ch8/data/rgb/1305031453.627706.png b/vSLAM/ch8/data/rgb/1305031453.627706.png new file mode 100644 index 00000000..bac83b35 Binary files /dev/null and b/vSLAM/ch8/data/rgb/1305031453.627706.png differ diff --git a/vSLAM/ch8/directMethod/.kdev4/directMethod.kdev4 b/vSLAM/ch8/directMethod/.kdev4/directMethod.kdev4 new file mode 100644 index 00000000..4e5ef63f --- /dev/null +++ b/vSLAM/ch8/directMethod/.kdev4/directMethod.kdev4 @@ -0,0 +1,18 @@ +[Buildset] +BuildItems=@Variant(\x00\x00\x00\t\x00\x00\x00\x00\x01\x00\x00\x00\x0b\x00\x00\x00\x00\x01\x00\x00\x00\x18\x00d\x00i\x00r\x00e\x00c\x00t\x00M\x00e\x00t\x00h\x00o\x00d) + +[CMake] +Build Directory Count=1 +Current Build Directory Index=0 +ProjectRootRelative=./ + +[CMake][CMake Build Directory 0] +Build Directory Path=file:///home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build +Build Type=Debug +CMake Binary=file:///usr/bin/cmake +Environment Profile= +Extra Arguments= +Install Directory=file:///usr/local + +[Project] +VersionControlSupport=kdevgit diff --git a/vSLAM/ch8/directMethod/build/CMakeCache.txt b/vSLAM/ch8/directMethod/build/CMakeCache.txt new file mode 100644 index 00000000..0f798b7e --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeCache.txt @@ -0,0 +1,449 @@ +# This is the CMakeCache file. +# For build in directory: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build +# It was generated by CMake: /usr/bin/cmake +# You can edit this file to change values found and used by cmake. +# If you do not want to change any of the values, simply exit the editor. +# If you do want to change a value, simply edit, save, and exit the editor. +# The syntax for the file is as follows: +# KEY:TYPE=VALUE +# KEY is the name of a variable in the cache. +# TYPE is a hint to GUIs for the type of VALUE, DO NOT EDIT TYPE!. +# VALUE is the current value for the KEY. + +######################## +# EXTERNAL cache entries +######################## + +//Path to a program. +CMAKE_AR:FILEPATH=/usr/bin/ar + +//Choose the type of build, options are: None(CMAKE_CXX_FLAGS or +// CMAKE_C_FLAGS used) Debug Release RelWithDebInfo MinSizeRel. +CMAKE_BUILD_TYPE:STRING=Debug + +//Enable/Disable color output during build. +CMAKE_COLOR_MAKEFILE:BOOL=ON + +//CXX compiler. +CMAKE_CXX_COMPILER:FILEPATH=/usr/bin/c++ + +//Flags used by the compiler during all build types. +CMAKE_CXX_FLAGS:STRING= + +//Flags used by the compiler during debug builds. +CMAKE_CXX_FLAGS_DEBUG:STRING=-g + +//Flags used by the compiler during release minsize builds. +CMAKE_CXX_FLAGS_MINSIZEREL:STRING=-Os -DNDEBUG + +//Flags used by the compiler during release builds (/MD /Ob1 /Oi +// /Ot /Oy /Gs will produce slightly less optimized but smaller +// files). +CMAKE_CXX_FLAGS_RELEASE:STRING=-O3 -DNDEBUG + +//Flags used by the compiler during Release with Debug Info builds. +CMAKE_CXX_FLAGS_RELWITHDEBINFO:STRING=-O2 -g -DNDEBUG + +//C compiler. +CMAKE_C_COMPILER:FILEPATH=/usr/bin/cc + +//Flags used by the compiler during all build types. +CMAKE_C_FLAGS:STRING= + +//Flags used by the compiler during debug builds. +CMAKE_C_FLAGS_DEBUG:STRING=-g + +//Flags used by the compiler during release minsize builds. +CMAKE_C_FLAGS_MINSIZEREL:STRING=-Os -DNDEBUG + +//Flags used by the compiler during release builds (/MD /Ob1 /Oi +// /Ot /Oy /Gs will produce slightly less optimized but smaller +// files). +CMAKE_C_FLAGS_RELEASE:STRING=-O3 -DNDEBUG + +//Flags used by the compiler during Release with Debug Info builds. +CMAKE_C_FLAGS_RELWITHDEBINFO:STRING=-O2 -g -DNDEBUG + +//Flags used by the linker. +CMAKE_EXE_LINKER_FLAGS:STRING=' ' + +//Flags used by the linker during debug builds. +CMAKE_EXE_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during release minsize builds. +CMAKE_EXE_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during release builds. +CMAKE_EXE_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during Release with Debug Info builds. +CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//Enable/Disable output of compile commands during generation. +CMAKE_EXPORT_COMPILE_COMMANDS:BOOL=OFF + +//Install path prefix, prepended onto install directories. +CMAKE_INSTALL_PREFIX:PATH=/usr/local + +//Path to a program. +CMAKE_LINKER:FILEPATH=/usr/bin/ld + +//Path to a program. +CMAKE_MAKE_PROGRAM:FILEPATH=/usr/bin/make + +//Flags used by the linker during the creation of modules. +CMAKE_MODULE_LINKER_FLAGS:STRING=' ' + +//Flags used by the linker during debug builds. +CMAKE_MODULE_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during release minsize builds. +CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during release builds. +CMAKE_MODULE_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during Release with Debug Info builds. +CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//Path to a program. +CMAKE_NM:FILEPATH=/usr/bin/nm + +//Path to a program. +CMAKE_OBJCOPY:FILEPATH=/usr/bin/objcopy + +//Path to a program. +CMAKE_OBJDUMP:FILEPATH=/usr/bin/objdump + +//Value Computed by CMake +CMAKE_PROJECT_NAME:STATIC=directMethod + +//Path to a program. +CMAKE_RANLIB:FILEPATH=/usr/bin/ranlib + +//Flags used by the linker during the creation of dll's. +CMAKE_SHARED_LINKER_FLAGS:STRING=' ' + +//Flags used by the linker during debug builds. +CMAKE_SHARED_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during release minsize builds. +CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during release builds. +CMAKE_SHARED_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during Release with Debug Info builds. +CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//If set, runtime paths are not added when installing shared libraries, +// but are added when building. +CMAKE_SKIP_INSTALL_RPATH:BOOL=NO + +//If set, runtime paths are not added when using shared libraries. +CMAKE_SKIP_RPATH:BOOL=NO + +//Flags used by the linker during the creation of static libraries. +CMAKE_STATIC_LINKER_FLAGS:STRING= + +//Flags used by the linker during debug builds. +CMAKE_STATIC_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during release minsize builds. +CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during release builds. +CMAKE_STATIC_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during Release with Debug Info builds. +CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//Path to a program. +CMAKE_STRIP:FILEPATH=/usr/bin/strip + +//If true, cmake will use relative paths in makefiles and projects. +CMAKE_USE_RELATIVE_PATHS:BOOL=OFF + +//If this value is on, makefiles will be generated without the +// .SILENT directive, and all commands will be echoed to the console +// during the make. This is useful for debugging only. With Visual +// Studio IDE projects all commands are done without /nologo. +CMAKE_VERBOSE_MAKEFILE:BOOL=FALSE + +//Path to a library. +G2O_CLI_LIBRARY:FILEPATH=/usr/local/lib/libg2o_cli.so + +//Path to a library. +G2O_CLI_LIBRARY_DEBUG:FILEPATH=G2O_CLI_LIBRARY_DEBUG-NOTFOUND + +//Path to a library. +G2O_CORE_LIBRARY:FILEPATH=/usr/local/lib/libg2o_core.so + +//Path to a library. +G2O_CORE_LIBRARY_DEBUG:FILEPATH=G2O_CORE_LIBRARY_DEBUG-NOTFOUND + +//Path to a file. +G2O_INCLUDE_DIR:PATH=/usr/local/include + +//Path to a library. +G2O_SOLVER_CHOLMOD:FILEPATH=/usr/local/lib/libg2o_solver_cholmod.so + +//Path to a library. +G2O_SOLVER_CHOLMOD_DEBUG:FILEPATH=G2O_SOLVER_CHOLMOD_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_CSPARSE:FILEPATH=/usr/local/lib/libg2o_solver_csparse.so + +//Path to a library. +G2O_SOLVER_CSPARSE_DEBUG:FILEPATH=G2O_SOLVER_CSPARSE_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_CSPARSE_EXTENSION:FILEPATH=/usr/local/lib/libg2o_csparse_extension.so + +//Path to a library. +G2O_SOLVER_CSPARSE_EXTENSION_DEBUG:FILEPATH=G2O_SOLVER_CSPARSE_EXTENSION_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_DENSE:FILEPATH=/usr/local/lib/libg2o_solver_dense.so + +//Path to a library. +G2O_SOLVER_DENSE_DEBUG:FILEPATH=G2O_SOLVER_DENSE_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_EIGEN:FILEPATH=/usr/local/lib/libg2o_solver_eigen.so + +//Path to a library. +G2O_SOLVER_EIGEN_DEBUG:FILEPATH=G2O_SOLVER_EIGEN_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_PCG:FILEPATH=/usr/local/lib/libg2o_solver_pcg.so + +//Path to a library. +G2O_SOLVER_PCG_DEBUG:FILEPATH=G2O_SOLVER_PCG_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_SLAM2D_LINEAR:FILEPATH=/usr/local/lib/libg2o_solver_slam2d_linear.so + +//Path to a library. +G2O_SOLVER_SLAM2D_LINEAR_DEBUG:FILEPATH=G2O_SOLVER_SLAM2D_LINEAR_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_STRUCTURE_ONLY:FILEPATH=/usr/local/lib/libg2o_solver_structure_only.so + +//Path to a library. +G2O_SOLVER_STRUCTURE_ONLY_DEBUG:FILEPATH=G2O_SOLVER_STRUCTURE_ONLY_DEBUG-NOTFOUND + +//Path to a library. +G2O_STUFF_LIBRARY:FILEPATH=/usr/local/lib/libg2o_stuff.so + +//Path to a library. +G2O_STUFF_LIBRARY_DEBUG:FILEPATH=G2O_STUFF_LIBRARY_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_DATA:FILEPATH=/usr/local/lib/libg2o_types_data.so + +//Path to a library. +G2O_TYPES_DATA_DEBUG:FILEPATH=G2O_TYPES_DATA_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_ICP:FILEPATH=/usr/local/lib/libg2o_types_icp.so + +//Path to a library. +G2O_TYPES_ICP_DEBUG:FILEPATH=G2O_TYPES_ICP_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_SBA:FILEPATH=/usr/local/lib/libg2o_types_sba.so + +//Path to a library. +G2O_TYPES_SBA_DEBUG:FILEPATH=G2O_TYPES_SBA_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_SCLAM2D:FILEPATH=/usr/local/lib/libg2o_types_sclam2d.so + +//Path to a library. +G2O_TYPES_SCLAM2D_DEBUG:FILEPATH=G2O_TYPES_SCLAM2D_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_SIM3:FILEPATH=/usr/local/lib/libg2o_types_sim3.so + +//Path to a library. +G2O_TYPES_SIM3_DEBUG:FILEPATH=G2O_TYPES_SIM3_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_SLAM2D:FILEPATH=/usr/local/lib/libg2o_types_slam2d.so + +//Path to a library. +G2O_TYPES_SLAM2D_DEBUG:FILEPATH=G2O_TYPES_SLAM2D_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_SLAM3D:FILEPATH=/usr/local/lib/libg2o_types_slam3d.so + +//Path to a library. +G2O_TYPES_SLAM3D_DEBUG:FILEPATH=G2O_TYPES_SLAM3D_DEBUG-NOTFOUND + +//Path where debug 3rdparty OpenCV dependencies are located +OpenCV_3RDPARTY_LIB_DIR_DBG:PATH=/usr/local/share/OpenCV/3rdparty/lib + +//Path where release 3rdparty OpenCV dependencies are located +OpenCV_3RDPARTY_LIB_DIR_OPT:PATH=/usr/local/share/OpenCV/3rdparty/lib + +OpenCV_CONFIG_PATH:FILEPATH=/usr/local/share/OpenCV + +//The directory containing a CMake configuration file for OpenCV. +OpenCV_DIR:PATH=/usr/local/share/OpenCV + +//Path where debug OpenCV libraries are located +OpenCV_LIB_DIR_DBG:PATH= + +//Path where release OpenCV libraries are located +OpenCV_LIB_DIR_OPT:PATH= + +//Value Computed by CMake +directMethod_BINARY_DIR:STATIC=/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build + +//Value Computed by CMake +directMethod_SOURCE_DIR:STATIC=/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod + + +######################## +# INTERNAL cache entries +######################## + +//ADVANCED property for variable: CMAKE_AR +CMAKE_AR-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_BUILD_TOOL +CMAKE_BUILD_TOOL-ADVANCED:INTERNAL=1 +//What is the target build tool cmake is generating for. +CMAKE_BUILD_TOOL:INTERNAL=/usr/bin/make +//This is the directory where this CMakeCache.txt was created +CMAKE_CACHEFILE_DIR:INTERNAL=/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build +//Major version of cmake used to create the current loaded cache +CMAKE_CACHE_MAJOR_VERSION:INTERNAL=2 +//Minor version of cmake used to create the current loaded cache +CMAKE_CACHE_MINOR_VERSION:INTERNAL=8 +//Patch version of cmake used to create the current loaded cache +CMAKE_CACHE_PATCH_VERSION:INTERNAL=12 +//ADVANCED property for variable: CMAKE_COLOR_MAKEFILE +CMAKE_COLOR_MAKEFILE-ADVANCED:INTERNAL=1 +//Path to CMake executable. +CMAKE_COMMAND:INTERNAL=/usr/bin/cmake +//Path to cpack program executable. +CMAKE_CPACK_COMMAND:INTERNAL=/usr/bin/cpack +//Path to ctest program executable. +CMAKE_CTEST_COMMAND:INTERNAL=/usr/bin/ctest +//ADVANCED property for variable: CMAKE_CXX_COMPILER +CMAKE_CXX_COMPILER-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS +CMAKE_CXX_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_DEBUG +CMAKE_CXX_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_MINSIZEREL +CMAKE_CXX_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_RELEASE +CMAKE_CXX_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_RELWITHDEBINFO +CMAKE_CXX_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_COMPILER +CMAKE_C_COMPILER-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS +CMAKE_C_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS_DEBUG +CMAKE_C_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS_MINSIZEREL +CMAKE_C_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS_RELEASE +CMAKE_C_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS_RELWITHDEBINFO +CMAKE_C_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//Executable file format +CMAKE_EXECUTABLE_FORMAT:INTERNAL=ELF +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS +CMAKE_EXE_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_DEBUG +CMAKE_EXE_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_MINSIZEREL +CMAKE_EXE_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_RELEASE +CMAKE_EXE_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXPORT_COMPILE_COMMANDS +CMAKE_EXPORT_COMPILE_COMMANDS-ADVANCED:INTERNAL=1 +//Name of generator. +CMAKE_GENERATOR:INTERNAL=Unix Makefiles +//Name of generator toolset. +CMAKE_GENERATOR_TOOLSET:INTERNAL= +//Start directory with the top level CMakeLists.txt file for this +// project +CMAKE_HOME_DIRECTORY:INTERNAL=/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod +//Install .so files without execute permission. +CMAKE_INSTALL_SO_NO_EXE:INTERNAL=1 +//ADVANCED property for variable: CMAKE_LINKER +CMAKE_LINKER-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MAKE_PROGRAM +CMAKE_MAKE_PROGRAM-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS +CMAKE_MODULE_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_DEBUG +CMAKE_MODULE_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL +CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_RELEASE +CMAKE_MODULE_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_NM +CMAKE_NM-ADVANCED:INTERNAL=1 +//number of local generators +CMAKE_NUMBER_OF_LOCAL_GENERATORS:INTERNAL=1 +//ADVANCED property for variable: CMAKE_OBJCOPY +CMAKE_OBJCOPY-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_OBJDUMP +CMAKE_OBJDUMP-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_RANLIB +CMAKE_RANLIB-ADVANCED:INTERNAL=1 +//Path to CMake installation. +CMAKE_ROOT:INTERNAL=/usr/share/cmake-2.8 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS +CMAKE_SHARED_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_DEBUG +CMAKE_SHARED_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL +CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_RELEASE +CMAKE_SHARED_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SKIP_INSTALL_RPATH +CMAKE_SKIP_INSTALL_RPATH-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SKIP_RPATH +CMAKE_SKIP_RPATH-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS +CMAKE_STATIC_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_DEBUG +CMAKE_STATIC_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL +CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_RELEASE +CMAKE_STATIC_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STRIP +CMAKE_STRIP-ADVANCED:INTERNAL=1 +//uname command +CMAKE_UNAME:INTERNAL=/bin/uname +//ADVANCED property for variable: CMAKE_USE_RELATIVE_PATHS +CMAKE_USE_RELATIVE_PATHS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_VERBOSE_MAKEFILE +CMAKE_VERBOSE_MAKEFILE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: OpenCV_3RDPARTY_LIB_DIR_DBG +OpenCV_3RDPARTY_LIB_DIR_DBG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: OpenCV_3RDPARTY_LIB_DIR_OPT +OpenCV_3RDPARTY_LIB_DIR_OPT-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: OpenCV_CONFIG_PATH +OpenCV_CONFIG_PATH-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: OpenCV_LIB_DIR_DBG +OpenCV_LIB_DIR_DBG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: OpenCV_LIB_DIR_OPT +OpenCV_LIB_DIR_OPT-ADVANCED:INTERNAL=1 + diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CMakeCCompiler.cmake b/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CMakeCCompiler.cmake new file mode 100644 index 00000000..f4a508be --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CMakeCCompiler.cmake @@ -0,0 +1,56 @@ +set(CMAKE_C_COMPILER "/usr/bin/cc") +set(CMAKE_C_COMPILER_ARG1 "") +set(CMAKE_C_COMPILER_ID "GNU") +set(CMAKE_C_COMPILER_VERSION "4.8.4") +set(CMAKE_C_PLATFORM_ID "Linux") + +set(CMAKE_AR "/usr/bin/ar") +set(CMAKE_RANLIB "/usr/bin/ranlib") +set(CMAKE_LINKER "/usr/bin/ld") +set(CMAKE_COMPILER_IS_GNUCC 1) +set(CMAKE_C_COMPILER_LOADED 1) +set(CMAKE_C_COMPILER_WORKS TRUE) +set(CMAKE_C_ABI_COMPILED TRUE) +set(CMAKE_COMPILER_IS_MINGW ) +set(CMAKE_COMPILER_IS_CYGWIN ) +if(CMAKE_COMPILER_IS_CYGWIN) + set(CYGWIN 1) + set(UNIX 1) +endif() + +set(CMAKE_C_COMPILER_ENV_VAR "CC") + +if(CMAKE_COMPILER_IS_MINGW) + set(MINGW 1) +endif() +set(CMAKE_C_COMPILER_ID_RUN 1) +set(CMAKE_C_SOURCE_FILE_EXTENSIONS c) +set(CMAKE_C_IGNORE_EXTENSIONS h;H;o;O;obj;OBJ;def;DEF;rc;RC) +set(CMAKE_C_LINKER_PREFERENCE 10) + +# Save compiler ABI information. +set(CMAKE_C_SIZEOF_DATA_PTR "8") +set(CMAKE_C_COMPILER_ABI "ELF") +set(CMAKE_C_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") + +if(CMAKE_C_SIZEOF_DATA_PTR) + set(CMAKE_SIZEOF_VOID_P "${CMAKE_C_SIZEOF_DATA_PTR}") +endif() + +if(CMAKE_C_COMPILER_ABI) + set(CMAKE_INTERNAL_PLATFORM_ABI "${CMAKE_C_COMPILER_ABI}") +endif() + +if(CMAKE_C_LIBRARY_ARCHITECTURE) + set(CMAKE_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") +endif() + + + + +set(CMAKE_C_IMPLICIT_LINK_LIBRARIES "c") +set(CMAKE_C_IMPLICIT_LINK_DIRECTORIES "/usr/lib/gcc/x86_64-linux-gnu/4.8;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib") +set(CMAKE_C_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES "") + + + diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake b/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake new file mode 100644 index 00000000..1ca40dbc --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake @@ -0,0 +1,57 @@ +set(CMAKE_CXX_COMPILER "/usr/bin/c++") +set(CMAKE_CXX_COMPILER_ARG1 "") +set(CMAKE_CXX_COMPILER_ID "GNU") +set(CMAKE_CXX_COMPILER_VERSION "4.8.4") +set(CMAKE_CXX_PLATFORM_ID "Linux") + +set(CMAKE_AR "/usr/bin/ar") +set(CMAKE_RANLIB "/usr/bin/ranlib") +set(CMAKE_LINKER "/usr/bin/ld") +set(CMAKE_COMPILER_IS_GNUCXX 1) +set(CMAKE_CXX_COMPILER_LOADED 1) +set(CMAKE_CXX_COMPILER_WORKS TRUE) +set(CMAKE_CXX_ABI_COMPILED TRUE) +set(CMAKE_COMPILER_IS_MINGW ) +set(CMAKE_COMPILER_IS_CYGWIN ) +if(CMAKE_COMPILER_IS_CYGWIN) + set(CYGWIN 1) + set(UNIX 1) +endif() + +set(CMAKE_CXX_COMPILER_ENV_VAR "CXX") + +if(CMAKE_COMPILER_IS_MINGW) + set(MINGW 1) +endif() +set(CMAKE_CXX_COMPILER_ID_RUN 1) +set(CMAKE_CXX_IGNORE_EXTENSIONS inl;h;hpp;HPP;H;o;O;obj;OBJ;def;DEF;rc;RC) +set(CMAKE_CXX_SOURCE_FILE_EXTENSIONS C;M;c++;cc;cpp;cxx;m;mm;CPP) +set(CMAKE_CXX_LINKER_PREFERENCE 30) +set(CMAKE_CXX_LINKER_PREFERENCE_PROPAGATES 1) + +# Save compiler ABI information. +set(CMAKE_CXX_SIZEOF_DATA_PTR "8") +set(CMAKE_CXX_COMPILER_ABI "ELF") +set(CMAKE_CXX_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") + +if(CMAKE_CXX_SIZEOF_DATA_PTR) + set(CMAKE_SIZEOF_VOID_P "${CMAKE_CXX_SIZEOF_DATA_PTR}") +endif() + +if(CMAKE_CXX_COMPILER_ABI) + set(CMAKE_INTERNAL_PLATFORM_ABI "${CMAKE_CXX_COMPILER_ABI}") +endif() + +if(CMAKE_CXX_LIBRARY_ARCHITECTURE) + set(CMAKE_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") +endif() + + + + +set(CMAKE_CXX_IMPLICIT_LINK_LIBRARIES "stdc++;m;c") +set(CMAKE_CXX_IMPLICIT_LINK_DIRECTORIES "/usr/lib/gcc/x86_64-linux-gnu/4.8;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib") +set(CMAKE_CXX_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES "") + + + diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_C.bin b/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_C.bin new file mode 100755 index 00000000..f909aaac Binary files /dev/null and b/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_C.bin differ diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_CXX.bin b/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_CXX.bin new file mode 100755 index 00000000..d6b41c89 Binary files /dev/null and b/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_CXX.bin differ diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CMakeSystem.cmake b/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CMakeSystem.cmake new file mode 100644 index 00000000..8444407c --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CMakeSystem.cmake @@ -0,0 +1,15 @@ +set(CMAKE_HOST_SYSTEM "Linux-4.4.0-94-generic") +set(CMAKE_HOST_SYSTEM_NAME "Linux") +set(CMAKE_HOST_SYSTEM_VERSION "4.4.0-94-generic") +set(CMAKE_HOST_SYSTEM_PROCESSOR "x86_64") + + + +set(CMAKE_SYSTEM "Linux-4.4.0-94-generic") +set(CMAKE_SYSTEM_NAME "Linux") +set(CMAKE_SYSTEM_VERSION "4.4.0-94-generic") +set(CMAKE_SYSTEM_PROCESSOR "x86_64") + +set(CMAKE_CROSSCOMPILING "FALSE") + +set(CMAKE_SYSTEM_LOADED 1) diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CompilerIdC/CMakeCCompilerId.c b/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CompilerIdC/CMakeCCompilerId.c new file mode 100644 index 00000000..cba81d4a --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CompilerIdC/CMakeCCompilerId.c @@ -0,0 +1,389 @@ +#ifdef __cplusplus +# error "A C++ compiler has been selected for C." +#endif + +/* Version number components: V=Version, R=Revision, P=Patch + Version date components: YYYY=Year, MM=Month, DD=Day */ + +#if defined(__18CXX) +# define ID_VOID_MAIN +#endif + +#if defined(__INTEL_COMPILER) || defined(__ICC) +# define COMPILER_ID "Intel" + /* __INTEL_COMPILER = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER/100) +# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER % 10) +# if defined(__INTEL_COMPILER_BUILD_DATE) + /* __INTEL_COMPILER_BUILD_DATE = YYYYMMDD */ +# define COMPILER_VERSION_TWEAK DEC(__INTEL_COMPILER_BUILD_DATE) +# endif + +#elif defined(__PATHCC__) +# define COMPILER_ID "PathScale" +# define COMPILER_VERSION_MAJOR DEC(__PATHCC__) +# define COMPILER_VERSION_MINOR DEC(__PATHCC_MINOR__) +# if defined(__PATHCC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__PATHCC_PATCHLEVEL__) +# endif + +#elif defined(__clang__) +# define COMPILER_ID "Clang" +# define COMPILER_VERSION_MAJOR DEC(__clang_major__) +# define COMPILER_VERSION_MINOR DEC(__clang_minor__) +# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__) + +#elif defined(__BORLANDC__) && defined(__CODEGEARC_VERSION__) +# define COMPILER_ID "Embarcadero" +# define COMPILER_VERSION_MAJOR HEX(__CODEGEARC_VERSION__>>24 & 0x00FF) +# define COMPILER_VERSION_MINOR HEX(__CODEGEARC_VERSION__>>16 & 0x00FF) +# define COMPILER_VERSION_PATCH HEX(__CODEGEARC_VERSION__ & 0xFFFF) + +#elif defined(__BORLANDC__) +# define COMPILER_ID "Borland" + /* __BORLANDC__ = 0xVRR */ +# define COMPILER_VERSION_MAJOR HEX(__BORLANDC__>>8) +# define COMPILER_VERSION_MINOR HEX(__BORLANDC__ & 0xFF) + +#elif defined(__WATCOMC__) +# define COMPILER_ID "Watcom" + /* __WATCOMC__ = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(__WATCOMC__ / 100) +# define COMPILER_VERSION_MINOR DEC(__WATCOMC__ % 100) + +#elif defined(__SUNPRO_C) +# define COMPILER_ID "SunPro" +# if __SUNPRO_C >= 0x5100 + /* __SUNPRO_C = 0xVRRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_C>>12) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_C>>4 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_C & 0xF) +# else + /* __SUNPRO_C = 0xVRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_C>>8) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_C>>4 & 0xF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_C & 0xF) +# endif + +#elif defined(__HP_cc) +# define COMPILER_ID "HP" + /* __HP_cc = VVRRPP */ +# define COMPILER_VERSION_MAJOR DEC(__HP_cc/10000) +# define COMPILER_VERSION_MINOR DEC(__HP_cc/100 % 100) +# define COMPILER_VERSION_PATCH DEC(__HP_cc % 100) + +#elif defined(__DECC) +# define COMPILER_ID "Compaq" + /* __DECC_VER = VVRRTPPPP */ +# define COMPILER_VERSION_MAJOR DEC(__DECC_VER/10000000) +# define COMPILER_VERSION_MINOR DEC(__DECC_VER/100000 % 100) +# define COMPILER_VERSION_PATCH DEC(__DECC_VER % 10000) + +#elif defined(__IBMC__) +# if defined(__COMPILER_VER__) +# define COMPILER_ID "zOS" +# else +# if __IBMC__ >= 800 +# define COMPILER_ID "XL" +# else +# define COMPILER_ID "VisualAge" +# endif + /* __IBMC__ = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__IBMC__/100) +# define COMPILER_VERSION_MINOR DEC(__IBMC__/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__IBMC__ % 10) +# endif + +#elif defined(__PGI) +# define COMPILER_ID "PGI" +# define COMPILER_VERSION_MAJOR DEC(__PGIC__) +# define COMPILER_VERSION_MINOR DEC(__PGIC_MINOR__) +# if defined(__PGIC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__PGIC_PATCHLEVEL__) +# endif + +#elif defined(_CRAYC) +# define COMPILER_ID "Cray" +# define COMPILER_VERSION_MAJOR DEC(_RELEASE) +# define COMPILER_VERSION_MINOR DEC(_RELEASE_MINOR) + +#elif defined(__TI_COMPILER_VERSION__) +# define COMPILER_ID "TI" + /* __TI_COMPILER_VERSION__ = VVVRRRPPP */ +# define COMPILER_VERSION_MAJOR DEC(__TI_COMPILER_VERSION__/1000000) +# define COMPILER_VERSION_MINOR DEC(__TI_COMPILER_VERSION__/1000 % 1000) +# define COMPILER_VERSION_PATCH DEC(__TI_COMPILER_VERSION__ % 1000) + +#elif defined(__TINYC__) +# define COMPILER_ID "TinyCC" + +#elif defined(__SCO_VERSION__) +# define COMPILER_ID "SCO" + +#elif defined(__GNUC__) +# define COMPILER_ID "GNU" +# define COMPILER_VERSION_MAJOR DEC(__GNUC__) +# define COMPILER_VERSION_MINOR DEC(__GNUC_MINOR__) +# if defined(__GNUC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__) +# endif + +#elif defined(_MSC_VER) +# define COMPILER_ID "MSVC" + /* _MSC_VER = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(_MSC_VER / 100) +# define COMPILER_VERSION_MINOR DEC(_MSC_VER % 100) +# if defined(_MSC_FULL_VER) +# if _MSC_VER >= 1400 + /* _MSC_FULL_VER = VVRRPPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 100000) +# else + /* _MSC_FULL_VER = VVRRPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 10000) +# endif +# endif +# if defined(_MSC_BUILD) +# define COMPILER_VERSION_TWEAK DEC(_MSC_BUILD) +# endif + +/* Analog VisualDSP++ >= 4.5.6 */ +#elif defined(__VISUALDSPVERSION__) +# define COMPILER_ID "ADSP" + /* __VISUALDSPVERSION__ = 0xVVRRPP00 */ +# define COMPILER_VERSION_MAJOR HEX(__VISUALDSPVERSION__>>24) +# define COMPILER_VERSION_MINOR HEX(__VISUALDSPVERSION__>>16 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__VISUALDSPVERSION__>>8 & 0xFF) + +/* Analog VisualDSP++ < 4.5.6 */ +#elif defined(__ADSPBLACKFIN__) || defined(__ADSPTS__) || defined(__ADSP21000__) +# define COMPILER_ID "ADSP" + +/* IAR Systems compiler for embedded systems. + http://www.iar.com */ +#elif defined(__IAR_SYSTEMS_ICC__ ) || defined(__IAR_SYSTEMS_ICC) +# define COMPILER_ID "IAR" + +/* sdcc, the small devices C compiler for embedded systems, + http://sdcc.sourceforge.net */ +#elif defined(SDCC) +# define COMPILER_ID "SDCC" + /* SDCC = VRP */ +# define COMPILER_VERSION_MAJOR DEC(SDCC/100) +# define COMPILER_VERSION_MINOR DEC(SDCC/10 % 10) +# define COMPILER_VERSION_PATCH DEC(SDCC % 10) + +#elif defined(_SGI_COMPILER_VERSION) || defined(_COMPILER_VERSION) +# define COMPILER_ID "MIPSpro" +# if defined(_SGI_COMPILER_VERSION) + /* _SGI_COMPILER_VERSION = VRP */ +# define COMPILER_VERSION_MAJOR DEC(_SGI_COMPILER_VERSION/100) +# define COMPILER_VERSION_MINOR DEC(_SGI_COMPILER_VERSION/10 % 10) +# define COMPILER_VERSION_PATCH DEC(_SGI_COMPILER_VERSION % 10) +# else + /* _COMPILER_VERSION = VRP */ +# define COMPILER_VERSION_MAJOR DEC(_COMPILER_VERSION/100) +# define COMPILER_VERSION_MINOR DEC(_COMPILER_VERSION/10 % 10) +# define COMPILER_VERSION_PATCH DEC(_COMPILER_VERSION % 10) +# endif + +/* This compiler is either not known or is too old to define an + identification macro. Try to identify the platform and guess that + it is the native compiler. */ +#elif defined(__sgi) +# define COMPILER_ID "MIPSpro" + +#elif defined(__hpux) || defined(__hpua) +# define COMPILER_ID "HP" + +#else /* unknown compiler */ +# define COMPILER_ID "" + +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_compiler = "INFO" ":" "compiler[" COMPILER_ID "]"; + +/* Identify known platforms by name. */ +#if defined(__linux) || defined(__linux__) || defined(linux) +# define PLATFORM_ID "Linux" + +#elif defined(__CYGWIN__) +# define PLATFORM_ID "Cygwin" + +#elif defined(__MINGW32__) +# define PLATFORM_ID "MinGW" + +#elif defined(__APPLE__) +# define PLATFORM_ID "Darwin" + +#elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32) +# define PLATFORM_ID "Windows" + +#elif defined(__FreeBSD__) || defined(__FreeBSD) +# define PLATFORM_ID "FreeBSD" + +#elif defined(__NetBSD__) || defined(__NetBSD) +# define PLATFORM_ID "NetBSD" + +#elif defined(__OpenBSD__) || defined(__OPENBSD) +# define PLATFORM_ID "OpenBSD" + +#elif defined(__sun) || defined(sun) +# define PLATFORM_ID "SunOS" + +#elif defined(_AIX) || defined(__AIX) || defined(__AIX__) || defined(__aix) || defined(__aix__) +# define PLATFORM_ID "AIX" + +#elif defined(__sgi) || defined(__sgi__) || defined(_SGI) +# define PLATFORM_ID "IRIX" + +#elif defined(__hpux) || defined(__hpux__) +# define PLATFORM_ID "HP-UX" + +#elif defined(__HAIKU__) +# define PLATFORM_ID "Haiku" + +#elif defined(__BeOS) || defined(__BEOS__) || defined(_BEOS) +# define PLATFORM_ID "BeOS" + +#elif defined(__QNX__) || defined(__QNXNTO__) +# define PLATFORM_ID "QNX" + +#elif defined(__tru64) || defined(_tru64) || defined(__TRU64__) +# define PLATFORM_ID "Tru64" + +#elif defined(__riscos) || defined(__riscos__) +# define PLATFORM_ID "RISCos" + +#elif defined(__sinix) || defined(__sinix__) || defined(__SINIX__) +# define PLATFORM_ID "SINIX" + +#elif defined(__UNIX_SV__) +# define PLATFORM_ID "UNIX_SV" + +#elif defined(__bsdos__) +# define PLATFORM_ID "BSDOS" + +#elif defined(_MPRAS) || defined(MPRAS) +# define PLATFORM_ID "MP-RAS" + +#elif defined(__osf) || defined(__osf__) +# define PLATFORM_ID "OSF1" + +#elif defined(_SCO_SV) || defined(SCO_SV) || defined(sco_sv) +# define PLATFORM_ID "SCO_SV" + +#elif defined(__ultrix) || defined(__ultrix__) || defined(_ULTRIX) +# define PLATFORM_ID "ULTRIX" + +#elif defined(__XENIX__) || defined(_XENIX) || defined(XENIX) +# define PLATFORM_ID "Xenix" + +#else /* unknown platform */ +# define PLATFORM_ID "" + +#endif + +/* For windows compilers MSVC and Intel we can determine + the architecture of the compiler being used. This is because + the compilers do not have flags that can change the architecture, + but rather depend on which compiler is being used +*/ +#if defined(_WIN32) && defined(_MSC_VER) +# if defined(_M_IA64) +# define ARCHITECTURE_ID "IA64" + +# elif defined(_M_X64) || defined(_M_AMD64) +# define ARCHITECTURE_ID "x64" + +# elif defined(_M_IX86) +# define ARCHITECTURE_ID "X86" + +# elif defined(_M_ARM) +# define ARCHITECTURE_ID "ARM" + +# elif defined(_M_MIPS) +# define ARCHITECTURE_ID "MIPS" + +# elif defined(_M_SH) +# define ARCHITECTURE_ID "SHx" + +# else /* unknown architecture */ +# define ARCHITECTURE_ID "" +# endif + +#else +# define ARCHITECTURE_ID "" +#endif + +/* Convert integer to decimal digit literals. */ +#define DEC(n) \ + ('0' + (((n) / 10000000)%10)), \ + ('0' + (((n) / 1000000)%10)), \ + ('0' + (((n) / 100000)%10)), \ + ('0' + (((n) / 10000)%10)), \ + ('0' + (((n) / 1000)%10)), \ + ('0' + (((n) / 100)%10)), \ + ('0' + (((n) / 10)%10)), \ + ('0' + ((n) % 10)) + +/* Convert integer to hex digit literals. */ +#define HEX(n) \ + ('0' + ((n)>>28 & 0xF)), \ + ('0' + ((n)>>24 & 0xF)), \ + ('0' + ((n)>>20 & 0xF)), \ + ('0' + ((n)>>16 & 0xF)), \ + ('0' + ((n)>>12 & 0xF)), \ + ('0' + ((n)>>8 & 0xF)), \ + ('0' + ((n)>>4 & 0xF)), \ + ('0' + ((n) & 0xF)) + +/* Construct a string literal encoding the version number components. */ +#ifdef COMPILER_VERSION_MAJOR +char const info_version[] = { + 'I', 'N', 'F', 'O', ':', + 'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','[', + COMPILER_VERSION_MAJOR, +# ifdef COMPILER_VERSION_MINOR + '.', COMPILER_VERSION_MINOR, +# ifdef COMPILER_VERSION_PATCH + '.', COMPILER_VERSION_PATCH, +# ifdef COMPILER_VERSION_TWEAK + '.', COMPILER_VERSION_TWEAK, +# endif +# endif +# endif + ']','\0'}; +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_platform = "INFO" ":" "platform[" PLATFORM_ID "]"; +char const* info_arch = "INFO" ":" "arch[" ARCHITECTURE_ID "]"; + + + +/*--------------------------------------------------------------------------*/ + +#ifdef ID_VOID_MAIN +void main() {} +#else +int main(int argc, char* argv[]) +{ + int require = 0; + require += info_compiler[argc]; + require += info_platform[argc]; + require += info_arch[argc]; +#ifdef COMPILER_VERSION_MAJOR + require += info_version[argc]; +#endif + (void)argv; + return require; +} +#endif diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CompilerIdC/a.out b/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CompilerIdC/a.out new file mode 100755 index 00000000..49a5ca2e Binary files /dev/null and b/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CompilerIdC/a.out differ diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CompilerIdCXX/CMakeCXXCompilerId.cpp b/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CompilerIdCXX/CMakeCXXCompilerId.cpp new file mode 100644 index 00000000..e8220b26 --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CompilerIdCXX/CMakeCXXCompilerId.cpp @@ -0,0 +1,377 @@ +/* This source file must have a .cpp extension so that all C++ compilers + recognize the extension without flags. Borland does not know .cxx for + example. */ +#ifndef __cplusplus +# error "A C compiler has been selected for C++." +#endif + +/* Version number components: V=Version, R=Revision, P=Patch + Version date components: YYYY=Year, MM=Month, DD=Day */ + +#if defined(__COMO__) +# define COMPILER_ID "Comeau" + /* __COMO_VERSION__ = VRR */ +# define COMPILER_VERSION_MAJOR DEC(__COMO_VERSION__ / 100) +# define COMPILER_VERSION_MINOR DEC(__COMO_VERSION__ % 100) + +#elif defined(__INTEL_COMPILER) || defined(__ICC) +# define COMPILER_ID "Intel" + /* __INTEL_COMPILER = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER/100) +# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER % 10) +# if defined(__INTEL_COMPILER_BUILD_DATE) + /* __INTEL_COMPILER_BUILD_DATE = YYYYMMDD */ +# define COMPILER_VERSION_TWEAK DEC(__INTEL_COMPILER_BUILD_DATE) +# endif + +#elif defined(__PATHCC__) +# define COMPILER_ID "PathScale" +# define COMPILER_VERSION_MAJOR DEC(__PATHCC__) +# define COMPILER_VERSION_MINOR DEC(__PATHCC_MINOR__) +# if defined(__PATHCC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__PATHCC_PATCHLEVEL__) +# endif + +#elif defined(__clang__) +# define COMPILER_ID "Clang" +# define COMPILER_VERSION_MAJOR DEC(__clang_major__) +# define COMPILER_VERSION_MINOR DEC(__clang_minor__) +# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__) + +#elif defined(__BORLANDC__) && defined(__CODEGEARC_VERSION__) +# define COMPILER_ID "Embarcadero" +# define COMPILER_VERSION_MAJOR HEX(__CODEGEARC_VERSION__>>24 & 0x00FF) +# define COMPILER_VERSION_MINOR HEX(__CODEGEARC_VERSION__>>16 & 0x00FF) +# define COMPILER_VERSION_PATCH HEX(__CODEGEARC_VERSION__ & 0xFFFF) + +#elif defined(__BORLANDC__) +# define COMPILER_ID "Borland" + /* __BORLANDC__ = 0xVRR */ +# define COMPILER_VERSION_MAJOR HEX(__BORLANDC__>>8) +# define COMPILER_VERSION_MINOR HEX(__BORLANDC__ & 0xFF) + +#elif defined(__WATCOMC__) +# define COMPILER_ID "Watcom" + /* __WATCOMC__ = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(__WATCOMC__ / 100) +# define COMPILER_VERSION_MINOR DEC(__WATCOMC__ % 100) + +#elif defined(__SUNPRO_CC) +# define COMPILER_ID "SunPro" +# if __SUNPRO_CC >= 0x5100 + /* __SUNPRO_CC = 0xVRRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_CC>>12) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_CC>>4 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_CC & 0xF) +# else + /* __SUNPRO_CC = 0xVRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_CC>>8) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_CC>>4 & 0xF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_CC & 0xF) +# endif + +#elif defined(__HP_aCC) +# define COMPILER_ID "HP" + /* __HP_aCC = VVRRPP */ +# define COMPILER_VERSION_MAJOR DEC(__HP_aCC/10000) +# define COMPILER_VERSION_MINOR DEC(__HP_aCC/100 % 100) +# define COMPILER_VERSION_PATCH DEC(__HP_aCC % 100) + +#elif defined(__DECCXX) +# define COMPILER_ID "Compaq" + /* __DECCXX_VER = VVRRTPPPP */ +# define COMPILER_VERSION_MAJOR DEC(__DECCXX_VER/10000000) +# define COMPILER_VERSION_MINOR DEC(__DECCXX_VER/100000 % 100) +# define COMPILER_VERSION_PATCH DEC(__DECCXX_VER % 10000) + +#elif defined(__IBMCPP__) +# if defined(__COMPILER_VER__) +# define COMPILER_ID "zOS" +# else +# if __IBMCPP__ >= 800 +# define COMPILER_ID "XL" +# else +# define COMPILER_ID "VisualAge" +# endif + /* __IBMCPP__ = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__IBMCPP__/100) +# define COMPILER_VERSION_MINOR DEC(__IBMCPP__/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__IBMCPP__ % 10) +# endif + +#elif defined(__PGI) +# define COMPILER_ID "PGI" +# define COMPILER_VERSION_MAJOR DEC(__PGIC__) +# define COMPILER_VERSION_MINOR DEC(__PGIC_MINOR__) +# if defined(__PGIC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__PGIC_PATCHLEVEL__) +# endif + +#elif defined(_CRAYC) +# define COMPILER_ID "Cray" +# define COMPILER_VERSION_MAJOR DEC(_RELEASE) +# define COMPILER_VERSION_MINOR DEC(_RELEASE_MINOR) + +#elif defined(__TI_COMPILER_VERSION__) +# define COMPILER_ID "TI" + /* __TI_COMPILER_VERSION__ = VVVRRRPPP */ +# define COMPILER_VERSION_MAJOR DEC(__TI_COMPILER_VERSION__/1000000) +# define COMPILER_VERSION_MINOR DEC(__TI_COMPILER_VERSION__/1000 % 1000) +# define COMPILER_VERSION_PATCH DEC(__TI_COMPILER_VERSION__ % 1000) + +#elif defined(__SCO_VERSION__) +# define COMPILER_ID "SCO" + +#elif defined(__GNUC__) +# define COMPILER_ID "GNU" +# define COMPILER_VERSION_MAJOR DEC(__GNUC__) +# define COMPILER_VERSION_MINOR DEC(__GNUC_MINOR__) +# if defined(__GNUC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__) +# endif + +#elif defined(_MSC_VER) +# define COMPILER_ID "MSVC" + /* _MSC_VER = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(_MSC_VER / 100) +# define COMPILER_VERSION_MINOR DEC(_MSC_VER % 100) +# if defined(_MSC_FULL_VER) +# if _MSC_VER >= 1400 + /* _MSC_FULL_VER = VVRRPPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 100000) +# else + /* _MSC_FULL_VER = VVRRPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 10000) +# endif +# endif +# if defined(_MSC_BUILD) +# define COMPILER_VERSION_TWEAK DEC(_MSC_BUILD) +# endif + +/* Analog VisualDSP++ >= 4.5.6 */ +#elif defined(__VISUALDSPVERSION__) +# define COMPILER_ID "ADSP" + /* __VISUALDSPVERSION__ = 0xVVRRPP00 */ +# define COMPILER_VERSION_MAJOR HEX(__VISUALDSPVERSION__>>24) +# define COMPILER_VERSION_MINOR HEX(__VISUALDSPVERSION__>>16 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__VISUALDSPVERSION__>>8 & 0xFF) + +/* Analog VisualDSP++ < 4.5.6 */ +#elif defined(__ADSPBLACKFIN__) || defined(__ADSPTS__) || defined(__ADSP21000__) +# define COMPILER_ID "ADSP" + +/* IAR Systems compiler for embedded systems. + http://www.iar.com */ +#elif defined(__IAR_SYSTEMS_ICC__ ) || defined(__IAR_SYSTEMS_ICC) +# define COMPILER_ID "IAR" + +#elif defined(_SGI_COMPILER_VERSION) || defined(_COMPILER_VERSION) +# define COMPILER_ID "MIPSpro" +# if defined(_SGI_COMPILER_VERSION) + /* _SGI_COMPILER_VERSION = VRP */ +# define COMPILER_VERSION_MAJOR DEC(_SGI_COMPILER_VERSION/100) +# define COMPILER_VERSION_MINOR DEC(_SGI_COMPILER_VERSION/10 % 10) +# define COMPILER_VERSION_PATCH DEC(_SGI_COMPILER_VERSION % 10) +# else + /* _COMPILER_VERSION = VRP */ +# define COMPILER_VERSION_MAJOR DEC(_COMPILER_VERSION/100) +# define COMPILER_VERSION_MINOR DEC(_COMPILER_VERSION/10 % 10) +# define COMPILER_VERSION_PATCH DEC(_COMPILER_VERSION % 10) +# endif + +/* This compiler is either not known or is too old to define an + identification macro. Try to identify the platform and guess that + it is the native compiler. */ +#elif defined(__sgi) +# define COMPILER_ID "MIPSpro" + +#elif defined(__hpux) || defined(__hpua) +# define COMPILER_ID "HP" + +#else /* unknown compiler */ +# define COMPILER_ID "" + +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_compiler = "INFO" ":" "compiler[" COMPILER_ID "]"; + +/* Identify known platforms by name. */ +#if defined(__linux) || defined(__linux__) || defined(linux) +# define PLATFORM_ID "Linux" + +#elif defined(__CYGWIN__) +# define PLATFORM_ID "Cygwin" + +#elif defined(__MINGW32__) +# define PLATFORM_ID "MinGW" + +#elif defined(__APPLE__) +# define PLATFORM_ID "Darwin" + +#elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32) +# define PLATFORM_ID "Windows" + +#elif defined(__FreeBSD__) || defined(__FreeBSD) +# define PLATFORM_ID "FreeBSD" + +#elif defined(__NetBSD__) || defined(__NetBSD) +# define PLATFORM_ID "NetBSD" + +#elif defined(__OpenBSD__) || defined(__OPENBSD) +# define PLATFORM_ID "OpenBSD" + +#elif defined(__sun) || defined(sun) +# define PLATFORM_ID "SunOS" + +#elif defined(_AIX) || defined(__AIX) || defined(__AIX__) || defined(__aix) || defined(__aix__) +# define PLATFORM_ID "AIX" + +#elif defined(__sgi) || defined(__sgi__) || defined(_SGI) +# define PLATFORM_ID "IRIX" + +#elif defined(__hpux) || defined(__hpux__) +# define PLATFORM_ID "HP-UX" + +#elif defined(__HAIKU__) +# define PLATFORM_ID "Haiku" + +#elif defined(__BeOS) || defined(__BEOS__) || defined(_BEOS) +# define PLATFORM_ID "BeOS" + +#elif defined(__QNX__) || defined(__QNXNTO__) +# define PLATFORM_ID "QNX" + +#elif defined(__tru64) || defined(_tru64) || defined(__TRU64__) +# define PLATFORM_ID "Tru64" + +#elif defined(__riscos) || defined(__riscos__) +# define PLATFORM_ID "RISCos" + +#elif defined(__sinix) || defined(__sinix__) || defined(__SINIX__) +# define PLATFORM_ID "SINIX" + +#elif defined(__UNIX_SV__) +# define PLATFORM_ID "UNIX_SV" + +#elif defined(__bsdos__) +# define PLATFORM_ID "BSDOS" + +#elif defined(_MPRAS) || defined(MPRAS) +# define PLATFORM_ID "MP-RAS" + +#elif defined(__osf) || defined(__osf__) +# define PLATFORM_ID "OSF1" + +#elif defined(_SCO_SV) || defined(SCO_SV) || defined(sco_sv) +# define PLATFORM_ID "SCO_SV" + +#elif defined(__ultrix) || defined(__ultrix__) || defined(_ULTRIX) +# define PLATFORM_ID "ULTRIX" + +#elif defined(__XENIX__) || defined(_XENIX) || defined(XENIX) +# define PLATFORM_ID "Xenix" + +#else /* unknown platform */ +# define PLATFORM_ID "" + +#endif + +/* For windows compilers MSVC and Intel we can determine + the architecture of the compiler being used. This is because + the compilers do not have flags that can change the architecture, + but rather depend on which compiler is being used +*/ +#if defined(_WIN32) && defined(_MSC_VER) +# if defined(_M_IA64) +# define ARCHITECTURE_ID "IA64" + +# elif defined(_M_X64) || defined(_M_AMD64) +# define ARCHITECTURE_ID "x64" + +# elif defined(_M_IX86) +# define ARCHITECTURE_ID "X86" + +# elif defined(_M_ARM) +# define ARCHITECTURE_ID "ARM" + +# elif defined(_M_MIPS) +# define ARCHITECTURE_ID "MIPS" + +# elif defined(_M_SH) +# define ARCHITECTURE_ID "SHx" + +# else /* unknown architecture */ +# define ARCHITECTURE_ID "" +# endif + +#else +# define ARCHITECTURE_ID "" +#endif + +/* Convert integer to decimal digit literals. */ +#define DEC(n) \ + ('0' + (((n) / 10000000)%10)), \ + ('0' + (((n) / 1000000)%10)), \ + ('0' + (((n) / 100000)%10)), \ + ('0' + (((n) / 10000)%10)), \ + ('0' + (((n) / 1000)%10)), \ + ('0' + (((n) / 100)%10)), \ + ('0' + (((n) / 10)%10)), \ + ('0' + ((n) % 10)) + +/* Convert integer to hex digit literals. */ +#define HEX(n) \ + ('0' + ((n)>>28 & 0xF)), \ + ('0' + ((n)>>24 & 0xF)), \ + ('0' + ((n)>>20 & 0xF)), \ + ('0' + ((n)>>16 & 0xF)), \ + ('0' + ((n)>>12 & 0xF)), \ + ('0' + ((n)>>8 & 0xF)), \ + ('0' + ((n)>>4 & 0xF)), \ + ('0' + ((n) & 0xF)) + +/* Construct a string literal encoding the version number components. */ +#ifdef COMPILER_VERSION_MAJOR +char const info_version[] = { + 'I', 'N', 'F', 'O', ':', + 'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','[', + COMPILER_VERSION_MAJOR, +# ifdef COMPILER_VERSION_MINOR + '.', COMPILER_VERSION_MINOR, +# ifdef COMPILER_VERSION_PATCH + '.', COMPILER_VERSION_PATCH, +# ifdef COMPILER_VERSION_TWEAK + '.', COMPILER_VERSION_TWEAK, +# endif +# endif +# endif + ']','\0'}; +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_platform = "INFO" ":" "platform[" PLATFORM_ID "]"; +char const* info_arch = "INFO" ":" "arch[" ARCHITECTURE_ID "]"; + + + +/*--------------------------------------------------------------------------*/ + +int main(int argc, char* argv[]) +{ + int require = 0; + require += info_compiler[argc]; + require += info_platform[argc]; +#ifdef COMPILER_VERSION_MAJOR + require += info_version[argc]; +#endif + (void)argv; + return require; +} diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CompilerIdCXX/a.out b/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CompilerIdCXX/a.out new file mode 100755 index 00000000..96c16077 Binary files /dev/null and b/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CompilerIdCXX/a.out differ diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeDirectoryInformation.cmake b/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeDirectoryInformation.cmake new file mode 100644 index 00000000..39bcf94e --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeDirectoryInformation.cmake @@ -0,0 +1,16 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Relative path conversion top directories. +SET(CMAKE_RELATIVE_PATH_TOP_SOURCE "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod") +SET(CMAKE_RELATIVE_PATH_TOP_BINARY "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build") + +# Force unix paths in dependencies. +SET(CMAKE_FORCE_UNIX_PATHS 1) + + +# The C and CXX include file regular expressions for this directory. +SET(CMAKE_C_INCLUDE_REGEX_SCAN "^.*$") +SET(CMAKE_C_INCLUDE_REGEX_COMPLAIN "^$") +SET(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN}) +SET(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN}) diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeOutput.log b/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeOutput.log new file mode 100644 index 00000000..3445bb96 --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeOutput.log @@ -0,0 +1,263 @@ +The system is: Linux - 4.4.0-94-generic - x86_64 +Compiling the C compiler identification source file "CMakeCCompilerId.c" succeeded. +Compiler: /usr/bin/cc +Build flags: +Id flags: + +The output was: +0 + + +Compilation of the C compiler identification source "CMakeCCompilerId.c" produced "a.out" + +The C compiler identification is GNU, found in "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CompilerIdC/a.out" + +Compiling the CXX compiler identification source file "CMakeCXXCompilerId.cpp" succeeded. +Compiler: /usr/bin/c++ +Build flags: +Id flags: + +The output was: +0 + + +Compilation of the CXX compiler identification source "CMakeCXXCompilerId.cpp" produced "a.out" + +The CXX compiler identification is GNU, found in "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/2.8.12.2/CompilerIdCXX/a.out" + +Determining if the C compiler works passed with the following output: +Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeTmp + +Run Build Command:/usr/bin/make "cmTryCompileExec4102795742/fast" +/usr/bin/make -f CMakeFiles/cmTryCompileExec4102795742.dir/build.make CMakeFiles/cmTryCompileExec4102795742.dir/build +make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeTmp' +/usr/bin/cmake -E cmake_progress_report /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeTmp/CMakeFiles 1 +Building C object CMakeFiles/cmTryCompileExec4102795742.dir/testCCompiler.c.o +/usr/bin/cc -o CMakeFiles/cmTryCompileExec4102795742.dir/testCCompiler.c.o -c /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeTmp/testCCompiler.c +Linking C executable cmTryCompileExec4102795742 +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec4102795742.dir/link.txt --verbose=1 +/usr/bin/cc CMakeFiles/cmTryCompileExec4102795742.dir/testCCompiler.c.o -o cmTryCompileExec4102795742 -rdynamic +make[1]: Leaving directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeTmp' + + +Detecting C compiler ABI info compiled with the following output: +Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeTmp + +Run Build Command:/usr/bin/make "cmTryCompileExec413085571/fast" +/usr/bin/make -f CMakeFiles/cmTryCompileExec413085571.dir/build.make CMakeFiles/cmTryCompileExec413085571.dir/build +make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeTmp' +/usr/bin/cmake -E cmake_progress_report /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeTmp/CMakeFiles 1 +Building C object CMakeFiles/cmTryCompileExec413085571.dir/CMakeCCompilerABI.c.o +/usr/bin/cc -o CMakeFiles/cmTryCompileExec413085571.dir/CMakeCCompilerABI.c.o -c /usr/share/cmake-2.8/Modules/CMakeCCompilerABI.c +Linking C executable cmTryCompileExec413085571 +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec413085571.dir/link.txt --verbose=1 +/usr/bin/cc -v CMakeFiles/cmTryCompileExec413085571.dir/CMakeCCompilerABI.c.o -o cmTryCompileExec413085571 -rdynamic +Using built-in specs. +COLLECT_GCC=/usr/bin/cc +COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/4.8/lto-wrapper +Target: x86_64-linux-gnu +Configured with: ../src/configure -v --with-pkgversion='Ubuntu 4.8.4-2ubuntu1~14.04.3' --with-bugurl=file:///usr/share/doc/gcc-4.8/README.Bugs --enable-languages=c,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-4.8 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --with-gxx-include-dir=/usr/include/c++/4.8 --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --enable-gnu-unique-object --disable-libmudflap --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-4.8-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu +Thread model: posix +gcc version 4.8.4 (Ubuntu 4.8.4-2ubuntu1~14.04.3) +COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/ +LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../:/lib/:/usr/lib/ +COLLECT_GCC_OPTIONS='-v' '-o' 'cmTryCompileExec413085571' '-rdynamic' '-mtune=generic' '-march=x86-64' + /usr/lib/gcc/x86_64-linux-gnu/4.8/collect2 --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTryCompileExec413085571 /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/4.8 -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../.. CMakeFiles/cmTryCompileExec413085571.dir/CMakeCCompilerABI.c.o -lgcc --as-needed -lgcc_s --no-as-needed -lc -lgcc --as-needed -lgcc_s --no-as-needed /usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o +make[1]: Leaving directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeTmp' + + +Parsed C implicit link information from above output: + link line regex: [^( *|.*[/\])(ld|([^/\]+-)?ld|collect2)[^/\]*( |$)] + ignore line: [Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeTmp] + ignore line: [] + ignore line: [Run Build Command:/usr/bin/make "cmTryCompileExec413085571/fast"] + ignore line: [/usr/bin/make -f CMakeFiles/cmTryCompileExec413085571.dir/build.make CMakeFiles/cmTryCompileExec413085571.dir/build] + ignore line: [make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeTmp'] + ignore line: [/usr/bin/cmake -E cmake_progress_report /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeTmp/CMakeFiles 1] + ignore line: [Building C object CMakeFiles/cmTryCompileExec413085571.dir/CMakeCCompilerABI.c.o] + ignore line: [/usr/bin/cc -o CMakeFiles/cmTryCompileExec413085571.dir/CMakeCCompilerABI.c.o -c /usr/share/cmake-2.8/Modules/CMakeCCompilerABI.c] + ignore line: [Linking C executable cmTryCompileExec413085571] + ignore line: [/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec413085571.dir/link.txt --verbose=1] + ignore line: [/usr/bin/cc -v CMakeFiles/cmTryCompileExec413085571.dir/CMakeCCompilerABI.c.o -o cmTryCompileExec413085571 -rdynamic ] + ignore line: [Using built-in specs.] + ignore line: [COLLECT_GCC=/usr/bin/cc] + ignore line: [COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/4.8/lto-wrapper] + ignore line: [Target: x86_64-linux-gnu] + ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 4.8.4-2ubuntu1~14.04.3' --with-bugurl=file:///usr/share/doc/gcc-4.8/README.Bugs --enable-languages=c,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-4.8 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --with-gxx-include-dir=/usr/include/c++/4.8 --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --enable-gnu-unique-object --disable-libmudflap --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-4.8-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu] + ignore line: [Thread model: posix] + ignore line: [gcc version 4.8.4 (Ubuntu 4.8.4-2ubuntu1~14.04.3) ] + ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/] + ignore line: [LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../:/lib/:/usr/lib/] + ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'cmTryCompileExec413085571' '-rdynamic' '-mtune=generic' '-march=x86-64'] + link line: [ /usr/lib/gcc/x86_64-linux-gnu/4.8/collect2 --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTryCompileExec413085571 /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/4.8 -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../.. CMakeFiles/cmTryCompileExec413085571.dir/CMakeCCompilerABI.c.o -lgcc --as-needed -lgcc_s --no-as-needed -lc -lgcc --as-needed -lgcc_s --no-as-needed /usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o] + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/collect2] ==> ignore + arg [--sysroot=/] ==> ignore + arg [--build-id] ==> ignore + arg [--eh-frame-hdr] ==> ignore + arg [-m] ==> ignore + arg [elf_x86_64] ==> ignore + arg [--hash-style=gnu] ==> ignore + arg [--as-needed] ==> ignore + arg [-export-dynamic] ==> ignore + arg [-dynamic-linker] ==> ignore + arg [/lib64/ld-linux-x86-64.so.2] ==> ignore + arg [-zrelro] ==> ignore + arg [-o] ==> ignore + arg [cmTryCompileExec413085571] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o] ==> ignore + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] + arg [-L/lib/x86_64-linux-gnu] ==> dir [/lib/x86_64-linux-gnu] + arg [-L/lib/../lib] ==> dir [/lib/../lib] + arg [-L/usr/lib/x86_64-linux-gnu] ==> dir [/usr/lib/x86_64-linux-gnu] + arg [-L/usr/lib/../lib] ==> dir [/usr/lib/../lib] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] + arg [CMakeFiles/cmTryCompileExec413085571.dir/CMakeCCompilerABI.c.o] ==> ignore + arg [-lgcc] ==> lib [gcc] + arg [--as-needed] ==> ignore + arg [-lgcc_s] ==> lib [gcc_s] + arg [--no-as-needed] ==> ignore + arg [-lc] ==> lib [c] + arg [-lgcc] ==> lib [gcc] + arg [--as-needed] ==> ignore + arg [-lgcc_s] ==> lib [gcc_s] + arg [--no-as-needed] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o] ==> ignore + remove lib [gcc] + remove lib [gcc_s] + remove lib [gcc] + remove lib [gcc_s] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8] ==> [/usr/lib/gcc/x86_64-linux-gnu/4.8] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] ==> [/usr/lib] + collapse library dir [/lib/x86_64-linux-gnu] ==> [/lib/x86_64-linux-gnu] + collapse library dir [/lib/../lib] ==> [/lib] + collapse library dir [/usr/lib/x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/../lib] ==> [/usr/lib] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] ==> [/usr/lib] + implicit libs: [c] + implicit dirs: [/usr/lib/gcc/x86_64-linux-gnu/4.8;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib] + implicit fwks: [] + + +Determining if the CXX compiler works passed with the following output: +Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeTmp + +Run Build Command:/usr/bin/make "cmTryCompileExec1652308689/fast" +/usr/bin/make -f CMakeFiles/cmTryCompileExec1652308689.dir/build.make CMakeFiles/cmTryCompileExec1652308689.dir/build +make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeTmp' +/usr/bin/cmake -E cmake_progress_report /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeTmp/CMakeFiles 1 +Building CXX object CMakeFiles/cmTryCompileExec1652308689.dir/testCXXCompiler.cxx.o +/usr/bin/c++ -o CMakeFiles/cmTryCompileExec1652308689.dir/testCXXCompiler.cxx.o -c /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeTmp/testCXXCompiler.cxx +Linking CXX executable cmTryCompileExec1652308689 +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec1652308689.dir/link.txt --verbose=1 +/usr/bin/c++ CMakeFiles/cmTryCompileExec1652308689.dir/testCXXCompiler.cxx.o -o cmTryCompileExec1652308689 -rdynamic +make[1]: Leaving directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeTmp' + + +Detecting CXX compiler ABI info compiled with the following output: +Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeTmp + +Run Build Command:/usr/bin/make "cmTryCompileExec2373443878/fast" +/usr/bin/make -f CMakeFiles/cmTryCompileExec2373443878.dir/build.make CMakeFiles/cmTryCompileExec2373443878.dir/build +make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeTmp' +/usr/bin/cmake -E cmake_progress_report /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeTmp/CMakeFiles 1 +Building CXX object CMakeFiles/cmTryCompileExec2373443878.dir/CMakeCXXCompilerABI.cpp.o +/usr/bin/c++ -o CMakeFiles/cmTryCompileExec2373443878.dir/CMakeCXXCompilerABI.cpp.o -c /usr/share/cmake-2.8/Modules/CMakeCXXCompilerABI.cpp +Linking CXX executable cmTryCompileExec2373443878 +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec2373443878.dir/link.txt --verbose=1 +/usr/bin/c++ -v CMakeFiles/cmTryCompileExec2373443878.dir/CMakeCXXCompilerABI.cpp.o -o cmTryCompileExec2373443878 -rdynamic +Using built-in specs. +COLLECT_GCC=/usr/bin/c++ +COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/4.8/lto-wrapper +Target: x86_64-linux-gnu +Configured with: ../src/configure -v --with-pkgversion='Ubuntu 4.8.4-2ubuntu1~14.04.3' --with-bugurl=file:///usr/share/doc/gcc-4.8/README.Bugs --enable-languages=c,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-4.8 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --with-gxx-include-dir=/usr/include/c++/4.8 --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --enable-gnu-unique-object --disable-libmudflap --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-4.8-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu +Thread model: posix +gcc version 4.8.4 (Ubuntu 4.8.4-2ubuntu1~14.04.3) +COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/ +LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../:/lib/:/usr/lib/ +COLLECT_GCC_OPTIONS='-v' '-o' 'cmTryCompileExec2373443878' '-rdynamic' '-shared-libgcc' '-mtune=generic' '-march=x86-64' + /usr/lib/gcc/x86_64-linux-gnu/4.8/collect2 --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTryCompileExec2373443878 /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/4.8 -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../.. CMakeFiles/cmTryCompileExec2373443878.dir/CMakeCXXCompilerABI.cpp.o -lstdc++ -lm -lgcc_s -lgcc -lc -lgcc_s -lgcc /usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o +make[1]: Leaving directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeTmp' + + +Parsed CXX implicit link information from above output: + link line regex: [^( *|.*[/\])(ld|([^/\]+-)?ld|collect2)[^/\]*( |$)] + ignore line: [Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeTmp] + ignore line: [] + ignore line: [Run Build Command:/usr/bin/make "cmTryCompileExec2373443878/fast"] + ignore line: [/usr/bin/make -f CMakeFiles/cmTryCompileExec2373443878.dir/build.make CMakeFiles/cmTryCompileExec2373443878.dir/build] + ignore line: [make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeTmp'] + ignore line: [/usr/bin/cmake -E cmake_progress_report /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/CMakeTmp/CMakeFiles 1] + ignore line: [Building CXX object CMakeFiles/cmTryCompileExec2373443878.dir/CMakeCXXCompilerABI.cpp.o] + ignore line: [/usr/bin/c++ -o CMakeFiles/cmTryCompileExec2373443878.dir/CMakeCXXCompilerABI.cpp.o -c /usr/share/cmake-2.8/Modules/CMakeCXXCompilerABI.cpp] + ignore line: [Linking CXX executable cmTryCompileExec2373443878] + ignore line: [/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec2373443878.dir/link.txt --verbose=1] + ignore line: [/usr/bin/c++ -v CMakeFiles/cmTryCompileExec2373443878.dir/CMakeCXXCompilerABI.cpp.o -o cmTryCompileExec2373443878 -rdynamic ] + ignore line: [Using built-in specs.] + ignore line: [COLLECT_GCC=/usr/bin/c++] + ignore line: [COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/4.8/lto-wrapper] + ignore line: [Target: x86_64-linux-gnu] + ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 4.8.4-2ubuntu1~14.04.3' --with-bugurl=file:///usr/share/doc/gcc-4.8/README.Bugs --enable-languages=c,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-4.8 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --with-gxx-include-dir=/usr/include/c++/4.8 --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --enable-gnu-unique-object --disable-libmudflap --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-4.8-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu] + ignore line: [Thread model: posix] + ignore line: [gcc version 4.8.4 (Ubuntu 4.8.4-2ubuntu1~14.04.3) ] + ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/] + ignore line: [LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../:/lib/:/usr/lib/] + ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'cmTryCompileExec2373443878' '-rdynamic' '-shared-libgcc' '-mtune=generic' '-march=x86-64'] + link line: [ /usr/lib/gcc/x86_64-linux-gnu/4.8/collect2 --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTryCompileExec2373443878 /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/4.8 -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../.. CMakeFiles/cmTryCompileExec2373443878.dir/CMakeCXXCompilerABI.cpp.o -lstdc++ -lm -lgcc_s -lgcc -lc -lgcc_s -lgcc /usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o] + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/collect2] ==> ignore + arg [--sysroot=/] ==> ignore + arg [--build-id] ==> ignore + arg [--eh-frame-hdr] ==> ignore + arg [-m] ==> ignore + arg [elf_x86_64] ==> ignore + arg [--hash-style=gnu] ==> ignore + arg [--as-needed] ==> ignore + arg [-export-dynamic] ==> ignore + arg [-dynamic-linker] ==> ignore + arg [/lib64/ld-linux-x86-64.so.2] ==> ignore + arg [-zrelro] ==> ignore + arg [-o] ==> ignore + arg [cmTryCompileExec2373443878] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o] ==> ignore + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] + arg [-L/lib/x86_64-linux-gnu] ==> dir [/lib/x86_64-linux-gnu] + arg [-L/lib/../lib] ==> dir [/lib/../lib] + arg [-L/usr/lib/x86_64-linux-gnu] ==> dir [/usr/lib/x86_64-linux-gnu] + arg [-L/usr/lib/../lib] ==> dir [/usr/lib/../lib] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] + arg [CMakeFiles/cmTryCompileExec2373443878.dir/CMakeCXXCompilerABI.cpp.o] ==> ignore + arg [-lstdc++] ==> lib [stdc++] + arg [-lm] ==> lib [m] + arg [-lgcc_s] ==> lib [gcc_s] + arg [-lgcc] ==> lib [gcc] + arg [-lc] ==> lib [c] + arg [-lgcc_s] ==> lib [gcc_s] + arg [-lgcc] ==> lib [gcc] + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o] ==> ignore + remove lib [gcc_s] + remove lib [gcc] + remove lib [gcc_s] + remove lib [gcc] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8] ==> [/usr/lib/gcc/x86_64-linux-gnu/4.8] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] ==> [/usr/lib] + collapse library dir [/lib/x86_64-linux-gnu] ==> [/lib/x86_64-linux-gnu] + collapse library dir [/lib/../lib] ==> [/lib] + collapse library dir [/usr/lib/x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/../lib] ==> [/usr/lib] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] ==> [/usr/lib] + implicit libs: [stdc++;m;c] + implicit dirs: [/usr/lib/gcc/x86_64-linux-gnu/4.8;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib] + implicit fwks: [] + + diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/Makefile.cmake b/vSLAM/ch8/directMethod/build/CMakeFiles/Makefile.cmake new file mode 100644 index 00000000..b0f74cd6 --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/Makefile.cmake @@ -0,0 +1,74 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# The generator used is: +SET(CMAKE_DEPENDS_GENERATOR "Unix Makefiles") + +# The top level Makefile was generated from the following files: +SET(CMAKE_MAKEFILE_DEPENDS + "CMakeCache.txt" + "../CMakeLists.txt" + "CMakeFiles/2.8.12.2/CMakeCCompiler.cmake" + "CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake" + "CMakeFiles/2.8.12.2/CMakeSystem.cmake" + "../cmake_modules/FindG2O.cmake" + "/usr/local/share/OpenCV/OpenCVConfig-version.cmake" + "/usr/local/share/OpenCV/OpenCVConfig.cmake" + "/usr/local/share/OpenCV/OpenCVModules-release.cmake" + "/usr/local/share/OpenCV/OpenCVModules.cmake" + "/usr/share/cmake-2.8/Modules/CMakeCCompiler.cmake.in" + "/usr/share/cmake-2.8/Modules/CMakeCCompilerABI.c" + "/usr/share/cmake-2.8/Modules/CMakeCInformation.cmake" + "/usr/share/cmake-2.8/Modules/CMakeCXXCompiler.cmake.in" + "/usr/share/cmake-2.8/Modules/CMakeCXXCompilerABI.cpp" + "/usr/share/cmake-2.8/Modules/CMakeCXXInformation.cmake" + "/usr/share/cmake-2.8/Modules/CMakeClDeps.cmake" + "/usr/share/cmake-2.8/Modules/CMakeCommonLanguageInclude.cmake" + "/usr/share/cmake-2.8/Modules/CMakeDetermineCCompiler.cmake" + "/usr/share/cmake-2.8/Modules/CMakeDetermineCXXCompiler.cmake" + "/usr/share/cmake-2.8/Modules/CMakeDetermineCompiler.cmake" + "/usr/share/cmake-2.8/Modules/CMakeDetermineCompilerABI.cmake" + "/usr/share/cmake-2.8/Modules/CMakeDetermineCompilerId.cmake" + "/usr/share/cmake-2.8/Modules/CMakeDetermineSystem.cmake" + "/usr/share/cmake-2.8/Modules/CMakeFindBinUtils.cmake" + "/usr/share/cmake-2.8/Modules/CMakeGenericSystem.cmake" + "/usr/share/cmake-2.8/Modules/CMakeParseImplicitLinkInfo.cmake" + "/usr/share/cmake-2.8/Modules/CMakeSystem.cmake.in" + "/usr/share/cmake-2.8/Modules/CMakeSystemSpecificInformation.cmake" + "/usr/share/cmake-2.8/Modules/CMakeTestCCompiler.cmake" + "/usr/share/cmake-2.8/Modules/CMakeTestCXXCompiler.cmake" + "/usr/share/cmake-2.8/Modules/CMakeTestCompilerCommon.cmake" + "/usr/share/cmake-2.8/Modules/CMakeUnixFindMake.cmake" + "/usr/share/cmake-2.8/Modules/Compiler/GNU-C.cmake" + "/usr/share/cmake-2.8/Modules/Compiler/GNU-CXX.cmake" + "/usr/share/cmake-2.8/Modules/Compiler/GNU.cmake" + "/usr/share/cmake-2.8/Modules/MultiArchCross.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux-CXX.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux-GNU-C.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux-GNU-CXX.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux-GNU.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux.cmake" + "/usr/share/cmake-2.8/Modules/Platform/UnixPaths.cmake" + ) + +# The corresponding makefile is: +SET(CMAKE_MAKEFILE_OUTPUTS + "Makefile" + "CMakeFiles/cmake.check_cache" + ) + +# Byproducts of CMake generate step: +SET(CMAKE_MAKEFILE_PRODUCTS + "CMakeFiles/2.8.12.2/CMakeSystem.cmake" + "CMakeFiles/2.8.12.2/CMakeCCompiler.cmake" + "CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake" + "CMakeFiles/2.8.12.2/CMakeCCompiler.cmake" + "CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake" + "CMakeFiles/CMakeDirectoryInformation.cmake" + ) + +# Dependency information for all targets: +SET(CMAKE_DEPEND_INFO_FILES + "CMakeFiles/direct_semidense.dir/DependInfo.cmake" + "CMakeFiles/direct_sparse.dir/DependInfo.cmake" + ) diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/Makefile2 b/vSLAM/ch8/directMethod/build/CMakeFiles/Makefile2 new file mode 100644 index 00000000..45553b6f --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/Makefile2 @@ -0,0 +1,134 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Default target executed when no arguments are given to make. +default_target: all +.PHONY : default_target + +# The main recursive all target +all: +.PHONY : all + +# The main recursive preinstall target +preinstall: +.PHONY : preinstall + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build + +#============================================================================= +# Target rules for target CMakeFiles/direct_semidense.dir + +# All Build rule for target. +CMakeFiles/direct_semidense.dir/all: + $(MAKE) -f CMakeFiles/direct_semidense.dir/build.make CMakeFiles/direct_semidense.dir/depend + $(MAKE) -f CMakeFiles/direct_semidense.dir/build.make CMakeFiles/direct_semidense.dir/build + $(CMAKE_COMMAND) -E cmake_progress_report /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles 1 + @echo "Built target direct_semidense" +.PHONY : CMakeFiles/direct_semidense.dir/all + +# Include target in all. +all: CMakeFiles/direct_semidense.dir/all +.PHONY : all + +# Build rule for subdir invocation for target. +CMakeFiles/direct_semidense.dir/rule: cmake_check_build_system + $(CMAKE_COMMAND) -E cmake_progress_start /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles 1 + $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/direct_semidense.dir/all + $(CMAKE_COMMAND) -E cmake_progress_start /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles 0 +.PHONY : CMakeFiles/direct_semidense.dir/rule + +# Convenience name for target. +direct_semidense: CMakeFiles/direct_semidense.dir/rule +.PHONY : direct_semidense + +# clean rule for target. +CMakeFiles/direct_semidense.dir/clean: + $(MAKE) -f CMakeFiles/direct_semidense.dir/build.make CMakeFiles/direct_semidense.dir/clean +.PHONY : CMakeFiles/direct_semidense.dir/clean + +# clean rule for target. +clean: CMakeFiles/direct_semidense.dir/clean +.PHONY : clean + +#============================================================================= +# Target rules for target CMakeFiles/direct_sparse.dir + +# All Build rule for target. +CMakeFiles/direct_sparse.dir/all: + $(MAKE) -f CMakeFiles/direct_sparse.dir/build.make CMakeFiles/direct_sparse.dir/depend + $(MAKE) -f CMakeFiles/direct_sparse.dir/build.make CMakeFiles/direct_sparse.dir/build + $(CMAKE_COMMAND) -E cmake_progress_report /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles 2 + @echo "Built target direct_sparse" +.PHONY : CMakeFiles/direct_sparse.dir/all + +# Include target in all. +all: CMakeFiles/direct_sparse.dir/all +.PHONY : all + +# Build rule for subdir invocation for target. +CMakeFiles/direct_sparse.dir/rule: cmake_check_build_system + $(CMAKE_COMMAND) -E cmake_progress_start /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles 1 + $(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/direct_sparse.dir/all + $(CMAKE_COMMAND) -E cmake_progress_start /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles 0 +.PHONY : CMakeFiles/direct_sparse.dir/rule + +# Convenience name for target. +direct_sparse: CMakeFiles/direct_sparse.dir/rule +.PHONY : direct_sparse + +# clean rule for target. +CMakeFiles/direct_sparse.dir/clean: + $(MAKE) -f CMakeFiles/direct_sparse.dir/build.make CMakeFiles/direct_sparse.dir/clean +.PHONY : CMakeFiles/direct_sparse.dir/clean + +# clean rule for target. +clean: CMakeFiles/direct_sparse.dir/clean +.PHONY : clean + +#============================================================================= +# Special targets to cleanup operation of make. + +# Special rule to run CMake to check the build system integrity. +# No rule that depends on this can have commands that come from listfiles +# because they might be regenerated. +cmake_check_build_system: + $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0 +.PHONY : cmake_check_build_system + diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/TargetDirectories.txt b/vSLAM/ch8/directMethod/build/CMakeFiles/TargetDirectories.txt new file mode 100644 index 00000000..7b0e2d13 --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/TargetDirectories.txt @@ -0,0 +1,2 @@ +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/cmake.check_cache b/vSLAM/ch8/directMethod/build/CMakeFiles/cmake.check_cache new file mode 100644 index 00000000..3dccd731 --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/cmake.check_cache @@ -0,0 +1 @@ +# This file is generated by cmake for dependency checking of the CMakeCache.txt file diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/CXX.includecache b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/CXX.includecache new file mode 100644 index 00000000..fba61b78 --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/CXX.includecache @@ -0,0 +1,2032 @@ +#IncludeRegexLine: ^[ ]*#[ ]*(include|import)[ ]*[<"]([^">]+)([">]) + +#IncludeRegexScan: ^.*$ + +#IncludeRegexComplain: ^$ + +#IncludeRegexTransform: + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/direct_semidense.cpp +iostream +- +fstream +- +list +- +vector +- +chrono +- +ctime +- +climits +- +opencv2/core/core.hpp +- +opencv2/imgproc/imgproc.hpp +- +opencv2/highgui/highgui.hpp +- +opencv2/features2d/features2d.hpp +- +g2o/core/base_unary_edge.h +- +g2o/core/block_solver.h +- +g2o/core/optimization_algorithm_levenberg.h +- +g2o/solvers/dense/linear_solver_dense.h +- +g2o/core/robust_kernel.h +- +g2o/types/sba/types_six_dof_expmap.h +- + +/usr/include/eigen3/Eigen/Cholesky +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/Cholesky/LLT.h +/usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/Cholesky/LDLT.h +/usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/Cholesky/LLT_MKL.h +/usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Core/util/Macros.h +/usr/include/eigen3/Eigen/src/Core/util/Macros.h +complex +- +src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +malloc.h +- +immintrin.h +- +emmintrin.h +- +xmmintrin.h +- +pmmintrin.h +- +tmmintrin.h +- +smmintrin.h +- +nmmintrin.h +- +altivec.h +- +arm_neon.h +- +omp.h +- +cerrno +- +cstddef +- +cstdlib +- +cmath +- +cassert +- +functional +- +iosfwd +- +cstring +- +string +- +limits +- +climits +- +algorithm +- +iostream +- +intrin.h +- +new +- +src/Core/util/Constants.h +/usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/Core/util/ForwardDeclarations.h +/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/Core/util/Meta.h +/usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/Core/util/StaticAssert.h +/usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/Core/util/XprHelper.h +/usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/Core/util/Memory.h +/usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/Core/NumTraits.h +/usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/Core/MathFunctions.h +/usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/Core/GenericPacketMath.h +/usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/Core/arch/SSE/PacketMath.h +/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/Core/arch/SSE/MathFunctions.h +/usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/Core/arch/SSE/Complex.h +/usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/Core/arch/AltiVec/PacketMath.h +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/Core/arch/AltiVec/Complex.h +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/Core/arch/NEON/PacketMath.h +/usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/Core/arch/NEON/Complex.h +/usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/Core/arch/Default/Settings.h +/usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/Core/Functors.h +/usr/include/eigen3/Eigen/src/Core/Functors.h +src/Core/DenseCoeffsBase.h +/usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/Core/DenseBase.h +/usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/Core/MatrixBase.h +/usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/Core/EigenBase.h +/usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/Core/Assign.h +/usr/include/eigen3/Eigen/src/Core/Assign.h +src/Core/util/BlasUtil.h +/usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/Core/DenseStorage.h +/usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/Core/NestByValue.h +/usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/Core/ForceAlignedAccess.h +/usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/Core/ReturnByValue.h +/usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/Core/NoAlias.h +/usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/Core/PlainObjectBase.h +/usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/Core/Matrix.h +/usr/include/eigen3/Eigen/src/Core/Matrix.h +src/Core/Array.h +/usr/include/eigen3/Eigen/src/Core/Array.h +src/Core/CwiseBinaryOp.h +/usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/Core/CwiseUnaryOp.h +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/Core/CwiseNullaryOp.h +/usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/Core/CwiseUnaryView.h +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/Core/SelfCwiseBinaryOp.h +/usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/Core/Dot.h +/usr/include/eigen3/Eigen/src/Core/Dot.h +src/Core/StableNorm.h +/usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/Core/MapBase.h +/usr/include/eigen3/Eigen/src/Core/MapBase.h +src/Core/Stride.h +/usr/include/eigen3/Eigen/src/Core/Stride.h +src/Core/Map.h +/usr/include/eigen3/Eigen/src/Core/Map.h +src/Core/Block.h +/usr/include/eigen3/Eigen/src/Core/Block.h +src/Core/VectorBlock.h +/usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/Core/Ref.h +/usr/include/eigen3/Eigen/src/Core/Ref.h +src/Core/Transpose.h +/usr/include/eigen3/Eigen/src/Core/Transpose.h +src/Core/DiagonalMatrix.h +/usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/Core/Diagonal.h +/usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/Core/DiagonalProduct.h +/usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/Core/PermutationMatrix.h +/usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/Core/Transpositions.h +/usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/Core/Redux.h +/usr/include/eigen3/Eigen/src/Core/Redux.h +src/Core/Visitor.h +/usr/include/eigen3/Eigen/src/Core/Visitor.h +src/Core/Fuzzy.h +/usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/Core/IO.h +/usr/include/eigen3/Eigen/src/Core/IO.h +src/Core/Swap.h +/usr/include/eigen3/Eigen/src/Core/Swap.h +src/Core/CommaInitializer.h +/usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/Core/Flagged.h +/usr/include/eigen3/Eigen/src/Core/Flagged.h +src/Core/ProductBase.h +/usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/Core/GeneralProduct.h +/usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/Core/TriangularMatrix.h +/usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/Core/SelfAdjointView.h +/usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/Core/products/GeneralBlockPanelKernel.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/Core/products/Parallelizer.h +/usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/Core/products/CoeffBasedProduct.h +/usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/Core/products/GeneralMatrixVector.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/Core/products/GeneralMatrixMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/Core/SolveTriangular.h +/usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/Core/products/GeneralMatrixMatrixTriangular.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/Core/products/SelfadjointMatrixVector.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/Core/products/SelfadjointMatrixMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/Core/products/SelfadjointProduct.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/Core/products/SelfadjointRank2Update.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/Core/products/TriangularMatrixVector.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/Core/products/TriangularMatrixMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/Core/products/TriangularSolverMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/Core/products/TriangularSolverVector.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/Core/BandMatrix.h +/usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/Core/CoreIterators.h +/usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/Core/BooleanRedux.h +/usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/Core/Select.h +/usr/include/eigen3/Eigen/src/Core/Select.h +src/Core/VectorwiseOp.h +/usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/Core/Random.h +/usr/include/eigen3/Eigen/src/Core/Random.h +src/Core/Replicate.h +/usr/include/eigen3/Eigen/src/Core/Replicate.h +src/Core/Reverse.h +/usr/include/eigen3/Eigen/src/Core/Reverse.h +src/Core/ArrayBase.h +/usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/Core/ArrayWrapper.h +/usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/Core/products/GeneralMatrixMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/Core/products/GeneralMatrixVector_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/Core/products/SelfadjointMatrixMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/Core/products/SelfadjointMatrixVector_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/Core/products/TriangularMatrixMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/Core/products/TriangularMatrixVector_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/Core/products/TriangularSolverMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/Core/Assign_MKL.h +/usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/Core/GlobalFunctions.h +/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +Eigen2Support +/usr/include/eigen3/Eigen/Eigen2Support + +/usr/include/eigen3/Eigen/Dense +Core +/usr/include/eigen3/Eigen/Core +LU +/usr/include/eigen3/Eigen/LU +Cholesky +/usr/include/eigen3/Eigen/Cholesky +QR +/usr/include/eigen3/Eigen/QR +SVD +/usr/include/eigen3/Eigen/SVD +Geometry +/usr/include/eigen3/Eigen/Geometry +Eigenvalues +/usr/include/eigen3/Eigen/Eigenvalues + +/usr/include/eigen3/Eigen/Eigen2Support +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Eigen2Support/Macros.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/Eigen2Support/Memory.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/Eigen2Support/Meta.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/Eigen2Support/Lazy.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/Eigen2Support/Cwise.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/Eigen2Support/CwiseOperators.h +/usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/Eigen2Support/TriangularSolver.h +/usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/Eigen2Support/Block.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/Eigen2Support/VectorBlock.h +/usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/Eigen2Support/Minor.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/Eigen2Support/MathFunctions.h +/usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +iostream +- + +/usr/include/eigen3/Eigen/Eigenvalues +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +Cholesky +/usr/include/eigen3/Eigen/Cholesky +Jacobi +/usr/include/eigen3/Eigen/Jacobi +Householder +/usr/include/eigen3/Eigen/Householder +LU +/usr/include/eigen3/Eigen/LU +Geometry +/usr/include/eigen3/Eigen/Geometry +src/Eigenvalues/Tridiagonalization.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/Eigenvalues/RealSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/Eigenvalues/EigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/Eigenvalues/SelfAdjointEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/Eigenvalues/HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/Eigenvalues/ComplexSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/Eigenvalues/ComplexEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/Eigenvalues/RealQZ.h +/usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/Eigenvalues/GeneralizedEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/Eigenvalues/MatrixBaseEigenvalues.h +/usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/Eigenvalues/RealSchur_MKL.h +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/Eigenvalues/ComplexSchur_MKL.h +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Geometry +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +SVD +/usr/include/eigen3/Eigen/SVD +LU +/usr/include/eigen3/Eigen/LU +limits +- +src/Geometry/OrthoMethods.h +/usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/Geometry/EulerAngles.h +/usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/Geometry/Homogeneous.h +/usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/Geometry/RotationBase.h +/usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/Geometry/Rotation2D.h +/usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/Geometry/Quaternion.h +/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/Geometry/AngleAxis.h +/usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/Geometry/Transform.h +/usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/Geometry/Translation.h +/usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/Geometry/Scaling.h +/usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/Geometry/Hyperplane.h +/usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/Geometry/ParametrizedLine.h +/usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/Geometry/AlignedBox.h +/usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/Geometry/Umeyama.h +/usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/Geometry/arch/Geometry_SSE.h +/usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/Eigen2Support/Geometry/All.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Householder +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Householder/Householder.h +/usr/include/eigen3/Eigen/src/Householder/Householder.h +src/Householder/HouseholderSequence.h +/usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/Householder/BlockHouseholder.h +/usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Jacobi +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Jacobi/Jacobi.h +/usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/LU +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/misc/Kernel.h +/usr/include/eigen3/Eigen/src/misc/Kernel.h +src/misc/Image.h +/usr/include/eigen3/Eigen/src/misc/Image.h +src/LU/FullPivLU.h +/usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/LU/PartialPivLU.h +/usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/LU/PartialPivLU_MKL.h +/usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/LU/Determinant.h +/usr/include/eigen3/Eigen/src/LU/Determinant.h +src/LU/Inverse.h +/usr/include/eigen3/Eigen/src/LU/Inverse.h +src/LU/arch/Inverse_SSE.h +/usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/Eigen2Support/LU.h +/usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/QR +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +Cholesky +/usr/include/eigen3/Eigen/Cholesky +Jacobi +/usr/include/eigen3/Eigen/Jacobi +Householder +/usr/include/eigen3/Eigen/Householder +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/QR/HouseholderQR.h +/usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/QR/FullPivHouseholderQR.h +/usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/QR/ColPivHouseholderQR.h +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/QR/HouseholderQR_MKL.h +/usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/QR/ColPivHouseholderQR_MKL.h +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/Eigen2Support/QR.h +/usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +Eigenvalues +/usr/include/eigen3/Eigen/Eigenvalues + +/usr/include/eigen3/Eigen/SVD +QR +/usr/include/eigen3/Eigen/QR +Householder +/usr/include/eigen3/Eigen/Householder +Jacobi +/usr/include/eigen3/Eigen/Jacobi +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/SVD/JacobiSVD.h +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/SVD/JacobiSVD_MKL.h +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/SVD/UpperBidiagonalization.h +/usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/Eigen2Support/SVD.h +/usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/StdVector +Core +/usr/include/eigen3/Eigen/Core +vector +- +src/StlSupport/StdVector.h +/usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + +/usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + +/usr/include/eigen3/Eigen/src/Cholesky/LLT.h + +/usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Cholesky/Eigen/src/Core/util/MKL_support.h +iostream +- + +/usr/include/eigen3/Eigen/src/Core/Array.h + +/usr/include/eigen3/Eigen/src/Core/ArrayBase.h +../plugins/CommonCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +../plugins/MatrixCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +../plugins/ArrayCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +../plugins/CommonCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +../plugins/MatrixCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +../plugins/ArrayCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + +/usr/include/eigen3/Eigen/src/Core/Assign.h + +/usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + +/usr/include/eigen3/Eigen/src/Core/BandMatrix.h + +/usr/include/eigen3/Eigen/src/Core/Block.h + +/usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + +/usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + +/usr/include/eigen3/Eigen/src/Core/CoreIterators.h + +/usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + +/usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + +/usr/include/eigen3/Eigen/src/Core/DenseBase.h +../plugins/BlockMethods.h +/usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + +/usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + +/usr/include/eigen3/Eigen/src/Core/DenseStorage.h + +/usr/include/eigen3/Eigen/src/Core/Diagonal.h + +/usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + +/usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + +/usr/include/eigen3/Eigen/src/Core/Dot.h + +/usr/include/eigen3/Eigen/src/Core/EigenBase.h + +/usr/include/eigen3/Eigen/src/Core/Flagged.h + +/usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + +/usr/include/eigen3/Eigen/src/Core/Functors.h + +/usr/include/eigen3/Eigen/src/Core/Fuzzy.h + +/usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + +/usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + +/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + +/usr/include/eigen3/Eigen/src/Core/IO.h + +/usr/include/eigen3/Eigen/src/Core/Map.h + +/usr/include/eigen3/Eigen/src/Core/MapBase.h + +/usr/include/eigen3/Eigen/src/Core/MathFunctions.h + +/usr/include/eigen3/Eigen/src/Core/Matrix.h + +/usr/include/eigen3/Eigen/src/Core/MatrixBase.h +../plugins/CommonCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +../plugins/CommonCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +../plugins/MatrixCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +../plugins/MatrixCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/Core/NestByValue.h + +/usr/include/eigen3/Eigen/src/Core/NoAlias.h + +/usr/include/eigen3/Eigen/src/Core/NumTraits.h + +/usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + +/usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + +/usr/include/eigen3/Eigen/src/Core/ProductBase.h + +/usr/include/eigen3/Eigen/src/Core/Random.h + +/usr/include/eigen3/Eigen/src/Core/Redux.h + +/usr/include/eigen3/Eigen/src/Core/Ref.h + +/usr/include/eigen3/Eigen/src/Core/Replicate.h + +/usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + +/usr/include/eigen3/Eigen/src/Core/Reverse.h + +/usr/include/eigen3/Eigen/src/Core/Select.h + +/usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + +/usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + +/usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + +/usr/include/eigen3/Eigen/src/Core/StableNorm.h + +/usr/include/eigen3/Eigen/src/Core/Stride.h + +/usr/include/eigen3/Eigen/src/Core/Swap.h + +/usr/include/eigen3/Eigen/src/Core/Transpose.h + +/usr/include/eigen3/Eigen/src/Core/Transpositions.h + +/usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + +/usr/include/eigen3/Eigen/src/Core/VectorBlock.h + +/usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + +/usr/include/eigen3/Eigen/src/Core/Visitor.h + +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + +/usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + +/usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + +/usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + +/usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + +/usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + +/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + +/usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + +/usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + +/usr/include/eigen3/Eigen/src/Core/util/Constants.h + +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + +/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + +/usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +mkl.h +- +mkl_lapacke.h +- + +/usr/include/eigen3/Eigen/src/Core/util/Macros.h +cstdlib +- +iostream +- + +/usr/include/eigen3/Eigen/src/Core/util/Memory.h +unistd.h +- + +/usr/include/eigen3/Eigen/src/Core/util/Meta.h + +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + +/usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +limits +- +RotationBase.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +Rotation2D.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +Quaternion.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +AngleAxis.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +Transform.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +Translation.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +Scaling.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +AlignedBox.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +Hyperplane.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +ParametrizedLine.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +RotationBase.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +Rotation2D.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +Quaternion.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +AngleAxis.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +Transform.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +Translation.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +Scaling.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +AlignedBox.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +Hyperplane.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +ParametrizedLine.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/././HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/././HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +./ComplexSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +./RealSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +./RealQZ.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +./Tridiagonalization.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +./Tridiagonalization.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + +/usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + +/usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + +/usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + +/usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + +/usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + +/usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + +/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + +/usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + +/usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + +/usr/include/eigen3/Eigen/src/Geometry/Scaling.h + +/usr/include/eigen3/Eigen/src/Geometry/Transform.h + +/usr/include/eigen3/Eigen/src/Geometry/Translation.h + +/usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + +/usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + +/usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + +/usr/include/eigen3/Eigen/src/Householder/Householder.h + +/usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + +/usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + +/usr/include/eigen3/Eigen/src/LU/Determinant.h + +/usr/include/eigen3/Eigen/src/LU/FullPivLU.h + +/usr/include/eigen3/Eigen/src/LU/Inverse.h + +/usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + +/usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/LU/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/QR/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + +/usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + +/usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/QR/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/SVD/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + +/usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +Eigen/src/StlSupport/details.h +/usr/include/eigen3/Eigen/src/StlSupport/Eigen/src/StlSupport/details.h + +/usr/include/eigen3/Eigen/src/StlSupport/details.h + +/usr/include/eigen3/Eigen/src/misc/Image.h + +/usr/include/eigen3/Eigen/src/misc/Kernel.h + +/usr/include/eigen3/Eigen/src/misc/Solve.h + +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + +/usr/local/include/g2o/config.h +g2o/core/eigen_types.h +- + +/usr/local/include/g2o/core/base_binary_edge.h +iostream +- +limits +- +base_edge.h +/usr/local/include/g2o/core/base_edge.h +robust_kernel.h +/usr/local/include/g2o/core/robust_kernel.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +base_binary_edge.hpp +/usr/local/include/g2o/core/base_binary_edge.hpp + +/usr/local/include/g2o/core/base_binary_edge.hpp + +/usr/local/include/g2o/core/base_edge.h +iostream +- +limits +- +Eigen/Core +- +optimizable_graph.h +/usr/local/include/g2o/core/optimizable_graph.h + +/usr/local/include/g2o/core/base_multi_edge.h +iostream +- +iomanip +- +limits +- +Eigen/StdVector +- +base_edge.h +/usr/local/include/g2o/core/base_edge.h +robust_kernel.h +/usr/local/include/g2o/core/robust_kernel.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +base_multi_edge.hpp +/usr/local/include/g2o/core/base_multi_edge.hpp + +/usr/local/include/g2o/core/base_multi_edge.hpp + +/usr/local/include/g2o/core/base_unary_edge.h +iostream +- +cassert +- +limits +- +base_edge.h +/usr/local/include/g2o/core/base_edge.h +robust_kernel.h +/usr/local/include/g2o/core/robust_kernel.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +base_unary_edge.hpp +/usr/local/include/g2o/core/base_unary_edge.hpp + +/usr/local/include/g2o/core/base_unary_edge.hpp + +/usr/local/include/g2o/core/base_vertex.h +optimizable_graph.h +/usr/local/include/g2o/core/optimizable_graph.h +creators.h +/usr/local/include/g2o/core/creators.h +g2o/stuff/macros.h +/usr/local/include/g2o/core/g2o/stuff/macros.h +Eigen/Core +- +Eigen/Dense +- +Eigen/Cholesky +- +Eigen/StdVector +- +stack +- +base_vertex.hpp +/usr/local/include/g2o/core/base_vertex.hpp + +/usr/local/include/g2o/core/base_vertex.hpp + +/usr/local/include/g2o/core/batch_stats.h +iostream +- +vector +- +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/block_solver.h +Eigen/Core +- +solver.h +/usr/local/include/g2o/core/solver.h +linear_solver.h +/usr/local/include/g2o/core/linear_solver.h +sparse_block_matrix.h +/usr/local/include/g2o/core/sparse_block_matrix.h +sparse_block_matrix_diagonal.h +/usr/local/include/g2o/core/sparse_block_matrix_diagonal.h +openmp_mutex.h +/usr/local/include/g2o/core/openmp_mutex.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +block_solver.hpp +/usr/local/include/g2o/core/block_solver.hpp + +/usr/local/include/g2o/core/block_solver.hpp +sparse_optimizer.h +/usr/local/include/g2o/core/sparse_optimizer.h +Eigen/LU +- +fstream +- +iomanip +- +g2o/stuff/timeutil.h +/usr/local/include/g2o/core/g2o/stuff/timeutil.h +g2o/stuff/macros.h +/usr/local/include/g2o/core/g2o/stuff/macros.h +g2o/stuff/misc.h +/usr/local/include/g2o/core/g2o/stuff/misc.h + +/usr/local/include/g2o/core/creators.h +hyper_graph.h +/usr/local/include/g2o/core/hyper_graph.h +string +- +typeinfo +- + +/usr/local/include/g2o/core/eigen_types.h +Eigen/Core +- +Eigen/Geometry +- + +/usr/local/include/g2o/core/g2o_core_api.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h + +/usr/local/include/g2o/core/hyper_graph.h +map +- +set +- +bitset +- +cassert +- +vector +- +limits +- +cstddef +- +unordered_map +- +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/jacobian_workspace.h +Eigen/Core +- +Eigen/StdVector +- +vector +- +cassert +- +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h +hyper_graph.h +/usr/local/include/g2o/core/hyper_graph.h + +/usr/local/include/g2o/core/linear_solver.h +sparse_block_matrix.h +/usr/local/include/g2o/core/sparse_block_matrix.h +sparse_block_matrix_ccs.h +/usr/local/include/g2o/core/sparse_block_matrix_ccs.h + +/usr/local/include/g2o/core/matrix_operations.h +Eigen/Core +- + +/usr/local/include/g2o/core/matrix_structure.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/openmp_mutex.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +omp.h +- +cassert +- + +/usr/local/include/g2o/core/optimizable_graph.h +set +- +iostream +- +list +- +limits +- +cmath +- +typeinfo +- +openmp_mutex.h +/usr/local/include/g2o/core/openmp_mutex.h +hyper_graph.h +/usr/local/include/g2o/core/hyper_graph.h +parameter.h +/usr/local/include/g2o/core/parameter.h +parameter_container.h +/usr/local/include/g2o/core/parameter_container.h +jacobian_workspace.h +/usr/local/include/g2o/core/jacobian_workspace.h +g2o/stuff/macros.h +/usr/local/include/g2o/core/g2o/stuff/macros.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/optimization_algorithm.h +vector +- +utility +- +iosfwd +- +g2o/stuff/property.h +/usr/local/include/g2o/core/g2o/stuff/property.h +hyper_graph.h +/usr/local/include/g2o/core/hyper_graph.h +sparse_block_matrix.h +/usr/local/include/g2o/core/sparse_block_matrix.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/optimization_algorithm_levenberg.h +optimization_algorithm_with_hessian.h +/usr/local/include/g2o/core/optimization_algorithm_with_hessian.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/optimization_algorithm_with_hessian.h +optimization_algorithm.h +/usr/local/include/g2o/core/optimization_algorithm.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/parameter.h +iosfwd +- +hyper_graph.h +/usr/local/include/g2o/core/hyper_graph.h + +/usr/local/include/g2o/core/parameter_container.h +iosfwd +- +map +- +string +- + +/usr/local/include/g2o/core/robust_kernel.h +memory +- +Eigen/Core +- +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/solver.h +hyper_graph.h +/usr/local/include/g2o/core/hyper_graph.h +batch_stats.h +/usr/local/include/g2o/core/batch_stats.h +sparse_block_matrix.h +/usr/local/include/g2o/core/sparse_block_matrix.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h +cstddef +- + +/usr/local/include/g2o/core/sparse_block_matrix.h +map +- +vector +- +fstream +- +iostream +- +iomanip +- +cassert +- +Eigen/Core +- +sparse_block_matrix_ccs.h +/usr/local/include/g2o/core/sparse_block_matrix_ccs.h +matrix_structure.h +/usr/local/include/g2o/core/matrix_structure.h +matrix_operations.h +/usr/local/include/g2o/core/matrix_operations.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +sparse_block_matrix.hpp +/usr/local/include/g2o/core/sparse_block_matrix.hpp + +/usr/local/include/g2o/core/sparse_block_matrix.hpp + +/usr/local/include/g2o/core/sparse_block_matrix_ccs.h +vector +- +cassert +- +Eigen/Core +- +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +matrix_operations.h +/usr/local/include/g2o/core/matrix_operations.h +unordered_map +- + +/usr/local/include/g2o/core/sparse_block_matrix_diagonal.h +vector +- +Eigen/Core +- +Eigen/StdVector +- +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +matrix_operations.h +/usr/local/include/g2o/core/matrix_operations.h + +/usr/local/include/g2o/core/sparse_optimizer.h +g2o/stuff/macros.h +/usr/local/include/g2o/core/g2o/stuff/macros.h +optimizable_graph.h +/usr/local/include/g2o/core/optimizable_graph.h +sparse_block_matrix.h +/usr/local/include/g2o/core/sparse_block_matrix.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h +batch_stats.h +/usr/local/include/g2o/core/batch_stats.h +map +- + +/usr/local/include/g2o/solvers/dense/linear_solver_dense.h +g2o/core/linear_solver.h +/usr/local/include/g2o/solvers/dense/g2o/core/linear_solver.h +g2o/core/batch_stats.h +/usr/local/include/g2o/solvers/dense/g2o/core/batch_stats.h +vector +- +utility +- +Eigen/Core +- +Eigen/Cholesky +- + +/usr/local/include/g2o/stuff/g2o_stuff_api.h +g2o/config.h +/usr/local/include/g2o/stuff/g2o/config.h + +/usr/local/include/g2o/stuff/macros.h +float.h +- +math.h +- + +/usr/local/include/g2o/stuff/misc.h +macros.h +/usr/local/include/g2o/stuff/macros.h +cmath +- + +/usr/local/include/g2o/stuff/property.h +string +- +map +- +sstream +- +string_tools.h +/usr/local/include/g2o/stuff/string_tools.h +g2o_stuff_api.h +/usr/local/include/g2o/stuff/g2o_stuff_api.h + +/usr/local/include/g2o/stuff/string_tools.h +string +- +sstream +- +cstdlib +- +vector +- +macros.h +/usr/local/include/g2o/stuff/macros.h +g2o_stuff_api.h +/usr/local/include/g2o/stuff/g2o_stuff_api.h + +/usr/local/include/g2o/stuff/timeutil.h +time.h +- +sys/time.h +- +string +- +g2o_stuff_api.h +/usr/local/include/g2o/stuff/g2o_stuff_api.h + +/usr/local/include/g2o/types/sba/g2o_types_sba_api.h +g2o/config.h +/usr/local/include/g2o/types/sba/g2o/config.h + +/usr/local/include/g2o/types/sba/sbacam.h +Eigen/Core +- +Eigen/Geometry +- +g2o/stuff/misc.h +/usr/local/include/g2o/types/sba/g2o/stuff/misc.h +g2o/stuff/macros.h +/usr/local/include/g2o/types/sba/g2o/stuff/macros.h +g2o/types/slam3d/se3quat.h +/usr/local/include/g2o/types/sba/g2o/types/slam3d/se3quat.h +g2o_types_sba_api.h +/usr/local/include/g2o/types/sba/g2o_types_sba_api.h + +/usr/local/include/g2o/types/sba/types_sba.h +g2o/core/base_vertex.h +/usr/local/include/g2o/types/sba/g2o/core/base_vertex.h +g2o/core/base_binary_edge.h +/usr/local/include/g2o/types/sba/g2o/core/base_binary_edge.h +g2o/core/base_multi_edge.h +/usr/local/include/g2o/types/sba/g2o/core/base_multi_edge.h +sbacam.h +/usr/local/include/g2o/types/sba/sbacam.h +Eigen/Geometry +- +iostream +- +g2o_types_sba_api.h +/usr/local/include/g2o/types/sba/g2o_types_sba_api.h + +/usr/local/include/g2o/types/sba/types_six_dof_expmap.h +g2o/core/base_vertex.h +/usr/local/include/g2o/types/sba/g2o/core/base_vertex.h +g2o/core/base_binary_edge.h +/usr/local/include/g2o/types/sba/g2o/core/base_binary_edge.h +g2o/types/slam3d/se3_ops.h +/usr/local/include/g2o/types/sba/g2o/types/slam3d/se3_ops.h +types_sba.h +/usr/local/include/g2o/types/sba/types_sba.h +Eigen/Geometry +- + +/usr/local/include/g2o/types/slam3d/g2o_types_slam3d_api.h +g2o/config.h +/usr/local/include/g2o/types/slam3d/g2o/config.h + +/usr/local/include/g2o/types/slam3d/se3_ops.h +Eigen/Core +- +Eigen/Geometry +- +g2o_types_slam3d_api.h +/usr/local/include/g2o/types/slam3d/g2o_types_slam3d_api.h +se3_ops.hpp +/usr/local/include/g2o/types/slam3d/se3_ops.hpp + +/usr/local/include/g2o/types/slam3d/se3_ops.hpp + +/usr/local/include/g2o/types/slam3d/se3quat.h +se3_ops.h +/usr/local/include/g2o/types/slam3d/se3_ops.h +Eigen/Core +- +Eigen/Geometry +- + +/usr/local/include/opencv/cxcore.h +opencv2/core/core_c.h +/usr/local/include/opencv/opencv2/core/core_c.h + +/usr/local/include/opencv2/calib3d.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/opencv2/features2d.hpp +opencv2/core/affine.hpp +/usr/local/include/opencv2/opencv2/core/affine.hpp +opencv2/calib3d/calib3d_c.h +/usr/local/include/opencv2/opencv2/calib3d/calib3d_c.h + +/usr/local/include/opencv2/calib3d/calib3d_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/calib3d/opencv2/core/core_c.h + +/usr/local/include/opencv2/core.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/opencv2/core/cvdef.h +opencv2/core/version.hpp +/usr/local/include/opencv2/opencv2/core/version.hpp +opencv2/core/base.hpp +/usr/local/include/opencv2/opencv2/core/base.hpp +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/opencv2/core/cvstd.hpp +opencv2/core/traits.hpp +/usr/local/include/opencv2/opencv2/core/traits.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/opencv2/core/matx.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/opencv2/core/types.hpp +opencv2/core/mat.hpp +/usr/local/include/opencv2/opencv2/core/mat.hpp +opencv2/core/persistence.hpp +/usr/local/include/opencv2/opencv2/core/persistence.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/opencv2/opencv.hpp +opencv2/xfeatures2d.hpp +/usr/local/include/opencv2/opencv2/xfeatures2d.hpp +opencv2/core/operations.hpp +/usr/local/include/opencv2/opencv2/core/operations.hpp +opencv2/core/cvstd.inl.hpp +/usr/local/include/opencv2/opencv2/core/cvstd.inl.hpp +opencv2/core/utility.hpp +/usr/local/include/opencv2/opencv2/core/utility.hpp +opencv2/core/optim.hpp +/usr/local/include/opencv2/opencv2/core/optim.hpp + +/usr/local/include/opencv2/core/affine.hpp +opencv2/core.hpp +- + +/usr/local/include/opencv2/core/base.hpp +climits +- +algorithm +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/core/opencv2/core/cvstd.hpp +opencv2/core/neon_utils.hpp +/usr/local/include/opencv2/core/opencv2/core/neon_utils.hpp + +/usr/local/include/opencv2/core/bufferpool.hpp + +/usr/local/include/opencv2/core/core.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/core_c.h +opencv2/core/types_c.h +/usr/local/include/opencv2/core/opencv2/core/types_c.h +cxcore.h +/usr/local/include/opencv2/core/cxcore.h +cxcore.h +/usr/local/include/opencv2/core/cxcore.h +opencv2/core/utility.hpp +/usr/local/include/opencv2/core/opencv2/core/utility.hpp + +/usr/local/include/opencv2/core/cvdef.h +limits.h +- +opencv2/core/hal/interface.h +/usr/local/include/opencv2/core/opencv2/core/hal/interface.h +emmintrin.h +- +pmmintrin.h +- +tmmintrin.h +- +smmintrin.h +- +nmmintrin.h +- +nmmintrin.h +- +popcntintrin.h +- +immintrin.h +- +immintrin.h +- +Intrin.h +- +arm_neon.h +/usr/local/include/opencv2/core/arm_neon.h +arm_neon.h +- +intrin.h +- + +/usr/local/include/opencv2/core/cvstd.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +cstddef +- +cstring +- +cctype +- +string +- +algorithm +- +utility +- +cstdlib +- +cmath +- +opencv2/core/ptr.inl.hpp +/usr/local/include/opencv2/core/opencv2/core/ptr.inl.hpp + +/usr/local/include/opencv2/core/cvstd.inl.hpp +complex +- +ostream +- + +/usr/local/include/opencv2/core/fast_math.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +fastmath.h +- +cmath +- +math.h +- +tegra_round.hpp +/usr/local/include/opencv2/core/tegra_round.hpp + +/usr/local/include/opencv2/core/hal/interface.h +cstddef +- +stddef.h +- +cstdint +- +stdint.h +- + +/usr/local/include/opencv2/core/mat.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/core/opencv2/core/matx.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/core/opencv2/core/types.hpp +opencv2/core/bufferpool.hpp +/usr/local/include/opencv2/core/opencv2/core/bufferpool.hpp +opencv2/core/mat.inl.hpp +/usr/local/include/opencv2/core/opencv2/core/mat.inl.hpp + +/usr/local/include/opencv2/core/mat.inl.hpp + +/usr/local/include/opencv2/core/matx.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/base.hpp +/usr/local/include/opencv2/core/opencv2/core/base.hpp +opencv2/core/traits.hpp +/usr/local/include/opencv2/core/opencv2/core/traits.hpp +opencv2/core/saturate.hpp +/usr/local/include/opencv2/core/opencv2/core/saturate.hpp + +/usr/local/include/opencv2/core/neon_utils.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h + +/usr/local/include/opencv2/core/operations.hpp +cstdio +- + +/usr/local/include/opencv2/core/optim.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/persistence.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/core/opencv2/core/types.hpp +opencv2/core/mat.hpp +/usr/local/include/opencv2/core/opencv2/core/mat.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/core/opencv2/opencv.hpp +time.h +- + +/usr/local/include/opencv2/core/ptr.inl.hpp +algorithm +- + +/usr/local/include/opencv2/core/saturate.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/fast_math.hpp +/usr/local/include/opencv2/core/opencv2/core/fast_math.hpp + +/usr/local/include/opencv2/core/traits.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h + +/usr/local/include/opencv2/core/types.hpp +climits +- +cfloat +- +vector +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/core/opencv2/core/cvstd.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/core/opencv2/core/matx.hpp + +/usr/local/include/opencv2/core/types_c.h +ipl.h +- +ipl/ipl.h +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +assert.h +- +stdlib.h +- +string.h +- +float.h +- +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/utility.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp +opencv2/core/core_c.h +/usr/local/include/opencv2/core/opencv2/core/core_c.h + +/usr/local/include/opencv2/core/version.hpp + +/usr/local/include/opencv2/features2d.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/flann/miniflann.hpp +/usr/local/include/opencv2/opencv2/flann/miniflann.hpp + +/usr/local/include/opencv2/features2d/features2d.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/features2d/opencv2/features2d.hpp + +/usr/local/include/opencv2/flann/config.h + +/usr/local/include/opencv2/flann/defines.h +config.h +/usr/local/include/opencv2/flann/config.h + +/usr/local/include/opencv2/flann/miniflann.hpp +opencv2/core.hpp +/usr/local/include/opencv2/flann/opencv2/core.hpp +opencv2/flann/defines.h +/usr/local/include/opencv2/flann/opencv2/flann/defines.h + +/usr/local/include/opencv2/highgui.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgcodecs.hpp +/usr/local/include/opencv2/opencv2/imgcodecs.hpp +opencv2/videoio.hpp +/usr/local/include/opencv2/opencv2/videoio.hpp +opencv2/highgui/highgui_c.h +/usr/local/include/opencv2/opencv2/highgui/highgui_c.h + +/usr/local/include/opencv2/highgui/highgui.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/highgui/opencv2/highgui.hpp + +/usr/local/include/opencv2/highgui/highgui_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/highgui/opencv2/core/core_c.h +opencv2/imgproc/imgproc_c.h +/usr/local/include/opencv2/highgui/opencv2/imgproc/imgproc_c.h +opencv2/imgcodecs/imgcodecs_c.h +/usr/local/include/opencv2/highgui/opencv2/imgcodecs/imgcodecs_c.h +opencv2/videoio/videoio_c.h +/usr/local/include/opencv2/highgui/opencv2/videoio/videoio_c.h + +/usr/local/include/opencv2/imgcodecs.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/opencv.hpp +- + +/usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/imgcodecs/opencv2/core/core_c.h + +/usr/local/include/opencv2/imgproc.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/core.hpp +- +opencv2/imgproc.hpp +- +opencv2/imgcodecs.hpp +- +opencv2/highgui.hpp +- +iostream +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +math.h +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/opencv2/highgui.hpp +opencv2/imgproc/imgproc_c.h +/usr/local/include/opencv2/opencv2/imgproc/imgproc_c.h + +/usr/local/include/opencv2/imgproc/imgproc.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/imgproc/opencv2/imgproc.hpp + +/usr/local/include/opencv2/imgproc/imgproc_c.h +opencv2/imgproc/types_c.h +/usr/local/include/opencv2/imgproc/opencv2/imgproc/types_c.h + +/usr/local/include/opencv2/imgproc/types_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/imgproc/opencv2/core/core_c.h + +/usr/local/include/opencv2/ml.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +float.h +- +map +- +iostream +- + +/usr/local/include/opencv2/objdetect.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/objdetect/detection_based_tracker.hpp +/usr/local/include/opencv2/opencv2/objdetect/detection_based_tracker.hpp +opencv2/objdetect/objdetect_c.h +/usr/local/include/opencv2/opencv2/objdetect/objdetect_c.h + +/usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +vector +- + +/usr/local/include/opencv2/objdetect/objdetect_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/objdetect/opencv2/core/core_c.h +deque +- +vector +- + +/usr/local/include/opencv2/opencv.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/photo.hpp +/usr/local/include/opencv2/opencv2/photo.hpp +opencv2/video.hpp +/usr/local/include/opencv2/opencv2/video.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/opencv2/features2d.hpp +opencv2/objdetect.hpp +/usr/local/include/opencv2/opencv2/objdetect.hpp +opencv2/calib3d.hpp +/usr/local/include/opencv2/opencv2/calib3d.hpp +opencv2/imgcodecs.hpp +/usr/local/include/opencv2/opencv2/imgcodecs.hpp +opencv2/videoio.hpp +/usr/local/include/opencv2/opencv2/videoio.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/opencv2/highgui.hpp +opencv2/ml.hpp +/usr/local/include/opencv2/opencv2/ml.hpp + +/usr/local/include/opencv2/photo.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/photo/photo_c.h +/usr/local/include/opencv2/opencv2/photo/photo_c.h + +/usr/local/include/opencv2/photo/photo_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/photo/opencv2/core/core_c.h + +/usr/local/include/opencv2/video.hpp +opencv2/video/tracking.hpp +/usr/local/include/opencv2/opencv2/video/tracking.hpp +opencv2/video/background_segm.hpp +/usr/local/include/opencv2/opencv2/video/background_segm.hpp +opencv2/video/tracking_c.h +/usr/local/include/opencv2/opencv2/video/tracking_c.h + +/usr/local/include/opencv2/video/background_segm.hpp +opencv2/core.hpp +/usr/local/include/opencv2/video/opencv2/core.hpp + +/usr/local/include/opencv2/video/tracking.hpp +opencv2/core.hpp +/usr/local/include/opencv2/video/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/video/opencv2/imgproc.hpp + +/usr/local/include/opencv2/video/tracking_c.h +opencv2/imgproc/types_c.h +/usr/local/include/opencv2/video/opencv2/imgproc/types_c.h + +/usr/local/include/opencv2/videoio.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/opencv2/opencv.hpp + +/usr/local/include/opencv2/videoio/videoio_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/videoio/opencv2/core/core_c.h + diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/DependInfo.cmake b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/DependInfo.cmake new file mode 100644 index 00000000..9f4e89f6 --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/DependInfo.cmake @@ -0,0 +1,23 @@ +# The set of languages for which implicit dependencies are needed: +SET(CMAKE_DEPENDS_LANGUAGES + "CXX" + ) +# The set of files for implicit dependencies of each language: +SET(CMAKE_DEPENDS_CHECK_CXX + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/direct_semidense.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o" + ) +SET(CMAKE_CXX_COMPILER_ID "GNU") + +# Targets to which this target links. +SET(CMAKE_TARGET_LINKED_INFO_FILES + ) + +# The include file search paths: +SET(CMAKE_C_TARGET_INCLUDE_PATH + "/usr/local/include/opencv" + "/usr/local/include" + "/usr/include/eigen3" + ) +SET(CMAKE_CXX_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) +SET(CMAKE_Fortran_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) +SET(CMAKE_ASM_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/build.make b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/build.make new file mode 100644 index 00000000..89500ffb --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/build.make @@ -0,0 +1,128 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build + +# Include any dependencies generated for this target. +include CMakeFiles/direct_semidense.dir/depend.make + +# Include the progress variables for this target. +include CMakeFiles/direct_semidense.dir/progress.make + +# Include the compile flags for this target's objects. +include CMakeFiles/direct_semidense.dir/flags.make + +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: CMakeFiles/direct_semidense.dir/flags.make +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: ../direct_semidense.cpp + $(CMAKE_COMMAND) -E cmake_progress_report /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles $(CMAKE_PROGRESS_1) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o" + /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o -c /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/direct_semidense.cpp + +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/direct_semidense.dir/direct_semidense.cpp.i" + /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -E /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/direct_semidense.cpp > CMakeFiles/direct_semidense.dir/direct_semidense.cpp.i + +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/direct_semidense.dir/direct_semidense.cpp.s" + /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -S /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/direct_semidense.cpp -o CMakeFiles/direct_semidense.dir/direct_semidense.cpp.s + +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o.requires: +.PHONY : CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o.requires + +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o.provides: CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o.requires + $(MAKE) -f CMakeFiles/direct_semidense.dir/build.make CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o.provides.build +.PHONY : CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o.provides + +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o.provides.build: CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o + +# Object files for target direct_semidense +direct_semidense_OBJECTS = \ +"CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o" + +# External object files for target direct_semidense +direct_semidense_EXTERNAL_OBJECTS = + +direct_semidense: CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o +direct_semidense: CMakeFiles/direct_semidense.dir/build.make +direct_semidense: /usr/local/lib/libopencv_viz.so.3.1.0 +direct_semidense: /usr/local/lib/libopencv_videostab.so.3.1.0 +direct_semidense: /usr/local/lib/libopencv_videoio.so.3.1.0 +direct_semidense: /usr/local/lib/libopencv_video.so.3.1.0 +direct_semidense: /usr/local/lib/libopencv_superres.so.3.1.0 +direct_semidense: /usr/local/lib/libopencv_stitching.so.3.1.0 +direct_semidense: /usr/local/lib/libopencv_shape.so.3.1.0 +direct_semidense: /usr/local/lib/libopencv_photo.so.3.1.0 +direct_semidense: /usr/local/lib/libopencv_objdetect.so.3.1.0 +direct_semidense: /usr/local/lib/libopencv_ml.so.3.1.0 +direct_semidense: /usr/local/lib/libopencv_imgproc.so.3.1.0 +direct_semidense: /usr/local/lib/libopencv_imgcodecs.so.3.1.0 +direct_semidense: /usr/local/lib/libopencv_highgui.so.3.1.0 +direct_semidense: /usr/local/lib/libopencv_flann.so.3.1.0 +direct_semidense: /usr/local/lib/libopencv_features2d.so.3.1.0 +direct_semidense: /usr/local/lib/libopencv_core.so.3.1.0 +direct_semidense: /usr/local/lib/libopencv_calib3d.so.3.1.0 +direct_semidense: /usr/local/lib/libopencv_features2d.so.3.1.0 +direct_semidense: /usr/local/lib/libopencv_ml.so.3.1.0 +direct_semidense: /usr/local/lib/libopencv_highgui.so.3.1.0 +direct_semidense: /usr/local/lib/libopencv_videoio.so.3.1.0 +direct_semidense: /usr/local/lib/libopencv_imgcodecs.so.3.1.0 +direct_semidense: /usr/local/lib/libopencv_flann.so.3.1.0 +direct_semidense: /usr/local/lib/libopencv_video.so.3.1.0 +direct_semidense: /usr/local/lib/libopencv_imgproc.so.3.1.0 +direct_semidense: /usr/local/lib/libopencv_core.so.3.1.0 +direct_semidense: CMakeFiles/direct_semidense.dir/link.txt + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --red --bold "Linking CXX executable direct_semidense" + $(CMAKE_COMMAND) -E cmake_link_script CMakeFiles/direct_semidense.dir/link.txt --verbose=$(VERBOSE) + +# Rule to build all files generated by this target. +CMakeFiles/direct_semidense.dir/build: direct_semidense +.PHONY : CMakeFiles/direct_semidense.dir/build + +CMakeFiles/direct_semidense.dir/requires: CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o.requires +.PHONY : CMakeFiles/direct_semidense.dir/requires + +CMakeFiles/direct_semidense.dir/clean: + $(CMAKE_COMMAND) -P CMakeFiles/direct_semidense.dir/cmake_clean.cmake +.PHONY : CMakeFiles/direct_semidense.dir/clean + +CMakeFiles/direct_semidense.dir/depend: + cd /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/DependInfo.cmake --color=$(COLOR) +.PHONY : CMakeFiles/direct_semidense.dir/depend + diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/cmake_clean.cmake b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/cmake_clean.cmake new file mode 100644 index 00000000..68e4240a --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/cmake_clean.cmake @@ -0,0 +1,10 @@ +FILE(REMOVE_RECURSE + "CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o" + "direct_semidense.pdb" + "direct_semidense" +) + +# Per-language clean rules from dependency scanning. +FOREACH(lang CXX) + INCLUDE(CMakeFiles/direct_semidense.dir/cmake_clean_${lang}.cmake OPTIONAL) +ENDFOREACH(lang) diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/depend.internal b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/depend.internal new file mode 100644 index 00000000..cc5a2eab --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/depend.internal @@ -0,0 +1,315 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/direct_semidense.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Dense + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/g2o/config.h + /usr/local/include/g2o/core/base_binary_edge.h + /usr/local/include/g2o/core/base_binary_edge.hpp + /usr/local/include/g2o/core/base_edge.h + /usr/local/include/g2o/core/base_multi_edge.h + /usr/local/include/g2o/core/base_multi_edge.hpp + /usr/local/include/g2o/core/base_unary_edge.h + /usr/local/include/g2o/core/base_unary_edge.hpp + /usr/local/include/g2o/core/base_vertex.h + /usr/local/include/g2o/core/base_vertex.hpp + /usr/local/include/g2o/core/batch_stats.h + /usr/local/include/g2o/core/block_solver.h + /usr/local/include/g2o/core/block_solver.hpp + /usr/local/include/g2o/core/creators.h + /usr/local/include/g2o/core/eigen_types.h + /usr/local/include/g2o/core/g2o_core_api.h + /usr/local/include/g2o/core/hyper_graph.h + /usr/local/include/g2o/core/jacobian_workspace.h + /usr/local/include/g2o/core/linear_solver.h + /usr/local/include/g2o/core/matrix_operations.h + /usr/local/include/g2o/core/matrix_structure.h + /usr/local/include/g2o/core/openmp_mutex.h + /usr/local/include/g2o/core/optimizable_graph.h + /usr/local/include/g2o/core/optimization_algorithm.h + /usr/local/include/g2o/core/optimization_algorithm_levenberg.h + /usr/local/include/g2o/core/optimization_algorithm_with_hessian.h + /usr/local/include/g2o/core/parameter.h + /usr/local/include/g2o/core/parameter_container.h + /usr/local/include/g2o/core/robust_kernel.h + /usr/local/include/g2o/core/solver.h + /usr/local/include/g2o/core/sparse_block_matrix.h + /usr/local/include/g2o/core/sparse_block_matrix.hpp + /usr/local/include/g2o/core/sparse_block_matrix_ccs.h + /usr/local/include/g2o/core/sparse_block_matrix_diagonal.h + /usr/local/include/g2o/core/sparse_optimizer.h + /usr/local/include/g2o/solvers/dense/linear_solver_dense.h + /usr/local/include/g2o/stuff/g2o_stuff_api.h + /usr/local/include/g2o/stuff/macros.h + /usr/local/include/g2o/stuff/misc.h + /usr/local/include/g2o/stuff/property.h + /usr/local/include/g2o/stuff/string_tools.h + /usr/local/include/g2o/stuff/timeutil.h + /usr/local/include/g2o/types/sba/g2o_types_sba_api.h + /usr/local/include/g2o/types/sba/sbacam.h + /usr/local/include/g2o/types/sba/types_sba.h + /usr/local/include/g2o/types/sba/types_six_dof_expmap.h + /usr/local/include/g2o/types/slam3d/g2o_types_slam3d_api.h + /usr/local/include/g2o/types/slam3d/se3_ops.h + /usr/local/include/g2o/types/slam3d/se3_ops.hpp + /usr/local/include/g2o/types/slam3d/se3quat.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/features2d/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/depend.make b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/depend.make new file mode 100644 index 00000000..40390b6c --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/depend.make @@ -0,0 +1,315 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: ../direct_semidense.cpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/Cholesky +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/Core +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/Dense +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/Geometry +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/Householder +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/Jacobi +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/LU +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/QR +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/SVD +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/StdVector +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/config.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/base_binary_edge.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/base_binary_edge.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/base_edge.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/base_multi_edge.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/base_multi_edge.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/base_unary_edge.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/base_unary_edge.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/base_vertex.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/base_vertex.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/batch_stats.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/block_solver.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/block_solver.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/creators.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/eigen_types.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/g2o_core_api.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/hyper_graph.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/jacobian_workspace.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/linear_solver.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/matrix_operations.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/matrix_structure.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/openmp_mutex.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/optimizable_graph.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/optimization_algorithm.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/optimization_algorithm_levenberg.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/optimization_algorithm_with_hessian.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/parameter.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/parameter_container.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/robust_kernel.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/solver.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/sparse_block_matrix.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/sparse_block_matrix.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/sparse_block_matrix_ccs.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/sparse_block_matrix_diagonal.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/core/sparse_optimizer.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/solvers/dense/linear_solver_dense.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/stuff/g2o_stuff_api.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/stuff/macros.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/stuff/misc.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/stuff/property.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/stuff/string_tools.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/stuff/timeutil.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/types/sba/g2o_types_sba_api.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/types/sba/sbacam.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/types/sba/types_sba.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/types/sba/types_six_dof_expmap.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/types/slam3d/g2o_types_slam3d_api.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/types/slam3d/se3_ops.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/types/slam3d/se3_ops.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/g2o/types/slam3d/se3quat.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv/cxcore.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/calib3d.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/core.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/core/affine.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/core/base.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/core/core.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/core/core_c.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/core/cvdef.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/core/mat.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/core/matx.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/core/operations.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/core/optim.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/core/traits.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/core/types.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/core/types_c.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/core/utility.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/core/version.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/features2d.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/features2d/features2d.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/flann/config.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/flann/defines.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/highgui.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/highgui/highgui.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/imgproc.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/imgproc/imgproc.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/ml.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/objdetect.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/opencv.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/photo.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/video.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/videoio.hpp +CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o new file mode 100644 index 00000000..bcd50995 Binary files /dev/null and b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o differ diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/flags.make b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/flags.make new file mode 100644 index 00000000..a8bf41a6 --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/flags.make @@ -0,0 +1,8 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# compile CXX with /usr/bin/c++ +CXX_FLAGS = -std=c++11 -O3 -O3 -DNDEBUG -I/usr/local/include/opencv -I/usr/local/include -I/usr/include/eigen3 + +CXX_DEFINES = + diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/link.txt b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/link.txt new file mode 100644 index 00000000..98d35ed9 --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/link.txt @@ -0,0 +1 @@ +/usr/bin/c++ -std=c++11 -O3 -O3 -DNDEBUG CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o -o direct_semidense -rdynamic /usr/local/lib/libopencv_viz.so.3.1.0 /usr/local/lib/libopencv_videostab.so.3.1.0 /usr/local/lib/libopencv_videoio.so.3.1.0 /usr/local/lib/libopencv_video.so.3.1.0 /usr/local/lib/libopencv_superres.so.3.1.0 /usr/local/lib/libopencv_stitching.so.3.1.0 /usr/local/lib/libopencv_shape.so.3.1.0 /usr/local/lib/libopencv_photo.so.3.1.0 /usr/local/lib/libopencv_objdetect.so.3.1.0 /usr/local/lib/libopencv_ml.so.3.1.0 /usr/local/lib/libopencv_imgproc.so.3.1.0 /usr/local/lib/libopencv_imgcodecs.so.3.1.0 /usr/local/lib/libopencv_highgui.so.3.1.0 /usr/local/lib/libopencv_flann.so.3.1.0 /usr/local/lib/libopencv_features2d.so.3.1.0 /usr/local/lib/libopencv_core.so.3.1.0 /usr/local/lib/libopencv_calib3d.so.3.1.0 -lg2o_core -lg2o_types_sba -lg2o_solver_csparse -lg2o_stuff -lg2o_csparse_extension /usr/local/lib/libopencv_features2d.so.3.1.0 /usr/local/lib/libopencv_ml.so.3.1.0 /usr/local/lib/libopencv_highgui.so.3.1.0 /usr/local/lib/libopencv_videoio.so.3.1.0 /usr/local/lib/libopencv_imgcodecs.so.3.1.0 /usr/local/lib/libopencv_flann.so.3.1.0 /usr/local/lib/libopencv_video.so.3.1.0 /usr/local/lib/libopencv_imgproc.so.3.1.0 /usr/local/lib/libopencv_core.so.3.1.0 -Wl,-rpath,/usr/local/lib diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/progress.make b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/progress.make new file mode 100644 index 00000000..781c7de2 --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_semidense.dir/progress.make @@ -0,0 +1,2 @@ +CMAKE_PROGRESS_1 = 1 + diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/CXX.includecache b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/CXX.includecache new file mode 100644 index 00000000..641bcb20 --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/CXX.includecache @@ -0,0 +1,2032 @@ +#IncludeRegexLine: ^[ ]*#[ ]*(include|import)[ ]*[<"]([^">]+)([">]) + +#IncludeRegexScan: ^.*$ + +#IncludeRegexComplain: ^$ + +#IncludeRegexTransform: + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/direct_sparse.cpp +iostream +- +fstream +- +list +- +vector +- +chrono +- +ctime +- +climits +- +opencv2/core/core.hpp +- +opencv2/imgproc/imgproc.hpp +- +opencv2/highgui/highgui.hpp +- +opencv2/features2d/features2d.hpp +- +g2o/core/base_unary_edge.h +- +g2o/core/block_solver.h +- +g2o/core/optimization_algorithm_levenberg.h +- +g2o/solvers/dense/linear_solver_dense.h +- +g2o/core/robust_kernel.h +- +g2o/types/sba/types_six_dof_expmap.h +- + +/usr/include/eigen3/Eigen/Cholesky +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/Cholesky/LLT.h +/usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/Cholesky/LDLT.h +/usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/Cholesky/LLT_MKL.h +/usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Core/util/Macros.h +/usr/include/eigen3/Eigen/src/Core/util/Macros.h +complex +- +src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +malloc.h +- +immintrin.h +- +emmintrin.h +- +xmmintrin.h +- +pmmintrin.h +- +tmmintrin.h +- +smmintrin.h +- +nmmintrin.h +- +altivec.h +- +arm_neon.h +- +omp.h +- +cerrno +- +cstddef +- +cstdlib +- +cmath +- +cassert +- +functional +- +iosfwd +- +cstring +- +string +- +limits +- +climits +- +algorithm +- +iostream +- +intrin.h +- +new +- +src/Core/util/Constants.h +/usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/Core/util/ForwardDeclarations.h +/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/Core/util/Meta.h +/usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/Core/util/StaticAssert.h +/usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/Core/util/XprHelper.h +/usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/Core/util/Memory.h +/usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/Core/NumTraits.h +/usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/Core/MathFunctions.h +/usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/Core/GenericPacketMath.h +/usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/Core/arch/SSE/PacketMath.h +/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/Core/arch/SSE/MathFunctions.h +/usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/Core/arch/SSE/Complex.h +/usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/Core/arch/AltiVec/PacketMath.h +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/Core/arch/AltiVec/Complex.h +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/Core/arch/NEON/PacketMath.h +/usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/Core/arch/NEON/Complex.h +/usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/Core/arch/Default/Settings.h +/usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/Core/Functors.h +/usr/include/eigen3/Eigen/src/Core/Functors.h +src/Core/DenseCoeffsBase.h +/usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/Core/DenseBase.h +/usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/Core/MatrixBase.h +/usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/Core/EigenBase.h +/usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/Core/Assign.h +/usr/include/eigen3/Eigen/src/Core/Assign.h +src/Core/util/BlasUtil.h +/usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/Core/DenseStorage.h +/usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/Core/NestByValue.h +/usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/Core/ForceAlignedAccess.h +/usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/Core/ReturnByValue.h +/usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/Core/NoAlias.h +/usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/Core/PlainObjectBase.h +/usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/Core/Matrix.h +/usr/include/eigen3/Eigen/src/Core/Matrix.h +src/Core/Array.h +/usr/include/eigen3/Eigen/src/Core/Array.h +src/Core/CwiseBinaryOp.h +/usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/Core/CwiseUnaryOp.h +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/Core/CwiseNullaryOp.h +/usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/Core/CwiseUnaryView.h +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/Core/SelfCwiseBinaryOp.h +/usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/Core/Dot.h +/usr/include/eigen3/Eigen/src/Core/Dot.h +src/Core/StableNorm.h +/usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/Core/MapBase.h +/usr/include/eigen3/Eigen/src/Core/MapBase.h +src/Core/Stride.h +/usr/include/eigen3/Eigen/src/Core/Stride.h +src/Core/Map.h +/usr/include/eigen3/Eigen/src/Core/Map.h +src/Core/Block.h +/usr/include/eigen3/Eigen/src/Core/Block.h +src/Core/VectorBlock.h +/usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/Core/Ref.h +/usr/include/eigen3/Eigen/src/Core/Ref.h +src/Core/Transpose.h +/usr/include/eigen3/Eigen/src/Core/Transpose.h +src/Core/DiagonalMatrix.h +/usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/Core/Diagonal.h +/usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/Core/DiagonalProduct.h +/usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/Core/PermutationMatrix.h +/usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/Core/Transpositions.h +/usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/Core/Redux.h +/usr/include/eigen3/Eigen/src/Core/Redux.h +src/Core/Visitor.h +/usr/include/eigen3/Eigen/src/Core/Visitor.h +src/Core/Fuzzy.h +/usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/Core/IO.h +/usr/include/eigen3/Eigen/src/Core/IO.h +src/Core/Swap.h +/usr/include/eigen3/Eigen/src/Core/Swap.h +src/Core/CommaInitializer.h +/usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/Core/Flagged.h +/usr/include/eigen3/Eigen/src/Core/Flagged.h +src/Core/ProductBase.h +/usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/Core/GeneralProduct.h +/usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/Core/TriangularMatrix.h +/usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/Core/SelfAdjointView.h +/usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/Core/products/GeneralBlockPanelKernel.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/Core/products/Parallelizer.h +/usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/Core/products/CoeffBasedProduct.h +/usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/Core/products/GeneralMatrixVector.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/Core/products/GeneralMatrixMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/Core/SolveTriangular.h +/usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/Core/products/GeneralMatrixMatrixTriangular.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/Core/products/SelfadjointMatrixVector.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/Core/products/SelfadjointMatrixMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/Core/products/SelfadjointProduct.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/Core/products/SelfadjointRank2Update.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/Core/products/TriangularMatrixVector.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/Core/products/TriangularMatrixMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/Core/products/TriangularSolverMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/Core/products/TriangularSolverVector.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/Core/BandMatrix.h +/usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/Core/CoreIterators.h +/usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/Core/BooleanRedux.h +/usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/Core/Select.h +/usr/include/eigen3/Eigen/src/Core/Select.h +src/Core/VectorwiseOp.h +/usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/Core/Random.h +/usr/include/eigen3/Eigen/src/Core/Random.h +src/Core/Replicate.h +/usr/include/eigen3/Eigen/src/Core/Replicate.h +src/Core/Reverse.h +/usr/include/eigen3/Eigen/src/Core/Reverse.h +src/Core/ArrayBase.h +/usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/Core/ArrayWrapper.h +/usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/Core/products/GeneralMatrixMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/Core/products/GeneralMatrixVector_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/Core/products/SelfadjointMatrixMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/Core/products/SelfadjointMatrixVector_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/Core/products/TriangularMatrixMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/Core/products/TriangularMatrixVector_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/Core/products/TriangularSolverMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/Core/Assign_MKL.h +/usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/Core/GlobalFunctions.h +/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +Eigen2Support +/usr/include/eigen3/Eigen/Eigen2Support + +/usr/include/eigen3/Eigen/Dense +Core +/usr/include/eigen3/Eigen/Core +LU +/usr/include/eigen3/Eigen/LU +Cholesky +/usr/include/eigen3/Eigen/Cholesky +QR +/usr/include/eigen3/Eigen/QR +SVD +/usr/include/eigen3/Eigen/SVD +Geometry +/usr/include/eigen3/Eigen/Geometry +Eigenvalues +/usr/include/eigen3/Eigen/Eigenvalues + +/usr/include/eigen3/Eigen/Eigen2Support +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Eigen2Support/Macros.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/Eigen2Support/Memory.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/Eigen2Support/Meta.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/Eigen2Support/Lazy.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/Eigen2Support/Cwise.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/Eigen2Support/CwiseOperators.h +/usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/Eigen2Support/TriangularSolver.h +/usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/Eigen2Support/Block.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/Eigen2Support/VectorBlock.h +/usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/Eigen2Support/Minor.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/Eigen2Support/MathFunctions.h +/usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +iostream +- + +/usr/include/eigen3/Eigen/Eigenvalues +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +Cholesky +/usr/include/eigen3/Eigen/Cholesky +Jacobi +/usr/include/eigen3/Eigen/Jacobi +Householder +/usr/include/eigen3/Eigen/Householder +LU +/usr/include/eigen3/Eigen/LU +Geometry +/usr/include/eigen3/Eigen/Geometry +src/Eigenvalues/Tridiagonalization.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/Eigenvalues/RealSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/Eigenvalues/EigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/Eigenvalues/SelfAdjointEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/Eigenvalues/HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/Eigenvalues/ComplexSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/Eigenvalues/ComplexEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/Eigenvalues/RealQZ.h +/usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/Eigenvalues/GeneralizedEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/Eigenvalues/MatrixBaseEigenvalues.h +/usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/Eigenvalues/RealSchur_MKL.h +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/Eigenvalues/ComplexSchur_MKL.h +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Geometry +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +SVD +/usr/include/eigen3/Eigen/SVD +LU +/usr/include/eigen3/Eigen/LU +limits +- +src/Geometry/OrthoMethods.h +/usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/Geometry/EulerAngles.h +/usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/Geometry/Homogeneous.h +/usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/Geometry/RotationBase.h +/usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/Geometry/Rotation2D.h +/usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/Geometry/Quaternion.h +/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/Geometry/AngleAxis.h +/usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/Geometry/Transform.h +/usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/Geometry/Translation.h +/usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/Geometry/Scaling.h +/usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/Geometry/Hyperplane.h +/usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/Geometry/ParametrizedLine.h +/usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/Geometry/AlignedBox.h +/usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/Geometry/Umeyama.h +/usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/Geometry/arch/Geometry_SSE.h +/usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/Eigen2Support/Geometry/All.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Householder +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Householder/Householder.h +/usr/include/eigen3/Eigen/src/Householder/Householder.h +src/Householder/HouseholderSequence.h +/usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/Householder/BlockHouseholder.h +/usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Jacobi +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Jacobi/Jacobi.h +/usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/LU +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/misc/Kernel.h +/usr/include/eigen3/Eigen/src/misc/Kernel.h +src/misc/Image.h +/usr/include/eigen3/Eigen/src/misc/Image.h +src/LU/FullPivLU.h +/usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/LU/PartialPivLU.h +/usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/LU/PartialPivLU_MKL.h +/usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/LU/Determinant.h +/usr/include/eigen3/Eigen/src/LU/Determinant.h +src/LU/Inverse.h +/usr/include/eigen3/Eigen/src/LU/Inverse.h +src/LU/arch/Inverse_SSE.h +/usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/Eigen2Support/LU.h +/usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/QR +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +Cholesky +/usr/include/eigen3/Eigen/Cholesky +Jacobi +/usr/include/eigen3/Eigen/Jacobi +Householder +/usr/include/eigen3/Eigen/Householder +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/QR/HouseholderQR.h +/usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/QR/FullPivHouseholderQR.h +/usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/QR/ColPivHouseholderQR.h +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/QR/HouseholderQR_MKL.h +/usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/QR/ColPivHouseholderQR_MKL.h +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/Eigen2Support/QR.h +/usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +Eigenvalues +/usr/include/eigen3/Eigen/Eigenvalues + +/usr/include/eigen3/Eigen/SVD +QR +/usr/include/eigen3/Eigen/QR +Householder +/usr/include/eigen3/Eigen/Householder +Jacobi +/usr/include/eigen3/Eigen/Jacobi +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/SVD/JacobiSVD.h +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/SVD/JacobiSVD_MKL.h +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/SVD/UpperBidiagonalization.h +/usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/Eigen2Support/SVD.h +/usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/StdVector +Core +/usr/include/eigen3/Eigen/Core +vector +- +src/StlSupport/StdVector.h +/usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + +/usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + +/usr/include/eigen3/Eigen/src/Cholesky/LLT.h + +/usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Cholesky/Eigen/src/Core/util/MKL_support.h +iostream +- + +/usr/include/eigen3/Eigen/src/Core/Array.h + +/usr/include/eigen3/Eigen/src/Core/ArrayBase.h +../plugins/CommonCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +../plugins/MatrixCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +../plugins/ArrayCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +../plugins/CommonCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +../plugins/MatrixCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +../plugins/ArrayCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + +/usr/include/eigen3/Eigen/src/Core/Assign.h + +/usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + +/usr/include/eigen3/Eigen/src/Core/BandMatrix.h + +/usr/include/eigen3/Eigen/src/Core/Block.h + +/usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + +/usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + +/usr/include/eigen3/Eigen/src/Core/CoreIterators.h + +/usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + +/usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + +/usr/include/eigen3/Eigen/src/Core/DenseBase.h +../plugins/BlockMethods.h +/usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + +/usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + +/usr/include/eigen3/Eigen/src/Core/DenseStorage.h + +/usr/include/eigen3/Eigen/src/Core/Diagonal.h + +/usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + +/usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + +/usr/include/eigen3/Eigen/src/Core/Dot.h + +/usr/include/eigen3/Eigen/src/Core/EigenBase.h + +/usr/include/eigen3/Eigen/src/Core/Flagged.h + +/usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + +/usr/include/eigen3/Eigen/src/Core/Functors.h + +/usr/include/eigen3/Eigen/src/Core/Fuzzy.h + +/usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + +/usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + +/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + +/usr/include/eigen3/Eigen/src/Core/IO.h + +/usr/include/eigen3/Eigen/src/Core/Map.h + +/usr/include/eigen3/Eigen/src/Core/MapBase.h + +/usr/include/eigen3/Eigen/src/Core/MathFunctions.h + +/usr/include/eigen3/Eigen/src/Core/Matrix.h + +/usr/include/eigen3/Eigen/src/Core/MatrixBase.h +../plugins/CommonCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +../plugins/CommonCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +../plugins/MatrixCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +../plugins/MatrixCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/Core/NestByValue.h + +/usr/include/eigen3/Eigen/src/Core/NoAlias.h + +/usr/include/eigen3/Eigen/src/Core/NumTraits.h + +/usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + +/usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + +/usr/include/eigen3/Eigen/src/Core/ProductBase.h + +/usr/include/eigen3/Eigen/src/Core/Random.h + +/usr/include/eigen3/Eigen/src/Core/Redux.h + +/usr/include/eigen3/Eigen/src/Core/Ref.h + +/usr/include/eigen3/Eigen/src/Core/Replicate.h + +/usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + +/usr/include/eigen3/Eigen/src/Core/Reverse.h + +/usr/include/eigen3/Eigen/src/Core/Select.h + +/usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + +/usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + +/usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + +/usr/include/eigen3/Eigen/src/Core/StableNorm.h + +/usr/include/eigen3/Eigen/src/Core/Stride.h + +/usr/include/eigen3/Eigen/src/Core/Swap.h + +/usr/include/eigen3/Eigen/src/Core/Transpose.h + +/usr/include/eigen3/Eigen/src/Core/Transpositions.h + +/usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + +/usr/include/eigen3/Eigen/src/Core/VectorBlock.h + +/usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + +/usr/include/eigen3/Eigen/src/Core/Visitor.h + +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + +/usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + +/usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + +/usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + +/usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + +/usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + +/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + +/usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + +/usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + +/usr/include/eigen3/Eigen/src/Core/util/Constants.h + +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + +/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + +/usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +mkl.h +- +mkl_lapacke.h +- + +/usr/include/eigen3/Eigen/src/Core/util/Macros.h +cstdlib +- +iostream +- + +/usr/include/eigen3/Eigen/src/Core/util/Memory.h +unistd.h +- + +/usr/include/eigen3/Eigen/src/Core/util/Meta.h + +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + +/usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +limits +- +RotationBase.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +Rotation2D.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +Quaternion.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +AngleAxis.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +Transform.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +Translation.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +Scaling.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +AlignedBox.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +Hyperplane.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +ParametrizedLine.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +RotationBase.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +Rotation2D.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +Quaternion.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +AngleAxis.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +Transform.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +Translation.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +Scaling.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +AlignedBox.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +Hyperplane.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +ParametrizedLine.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/././HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/././HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +./ComplexSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +./RealSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +./RealQZ.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +./Tridiagonalization.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +./Tridiagonalization.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + +/usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + +/usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + +/usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + +/usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + +/usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + +/usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + +/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + +/usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + +/usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + +/usr/include/eigen3/Eigen/src/Geometry/Scaling.h + +/usr/include/eigen3/Eigen/src/Geometry/Transform.h + +/usr/include/eigen3/Eigen/src/Geometry/Translation.h + +/usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + +/usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + +/usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + +/usr/include/eigen3/Eigen/src/Householder/Householder.h + +/usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + +/usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + +/usr/include/eigen3/Eigen/src/LU/Determinant.h + +/usr/include/eigen3/Eigen/src/LU/FullPivLU.h + +/usr/include/eigen3/Eigen/src/LU/Inverse.h + +/usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + +/usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/LU/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/QR/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + +/usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + +/usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/QR/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/SVD/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + +/usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +Eigen/src/StlSupport/details.h +/usr/include/eigen3/Eigen/src/StlSupport/Eigen/src/StlSupport/details.h + +/usr/include/eigen3/Eigen/src/StlSupport/details.h + +/usr/include/eigen3/Eigen/src/misc/Image.h + +/usr/include/eigen3/Eigen/src/misc/Kernel.h + +/usr/include/eigen3/Eigen/src/misc/Solve.h + +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + +/usr/local/include/g2o/config.h +g2o/core/eigen_types.h +- + +/usr/local/include/g2o/core/base_binary_edge.h +iostream +- +limits +- +base_edge.h +/usr/local/include/g2o/core/base_edge.h +robust_kernel.h +/usr/local/include/g2o/core/robust_kernel.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +base_binary_edge.hpp +/usr/local/include/g2o/core/base_binary_edge.hpp + +/usr/local/include/g2o/core/base_binary_edge.hpp + +/usr/local/include/g2o/core/base_edge.h +iostream +- +limits +- +Eigen/Core +- +optimizable_graph.h +/usr/local/include/g2o/core/optimizable_graph.h + +/usr/local/include/g2o/core/base_multi_edge.h +iostream +- +iomanip +- +limits +- +Eigen/StdVector +- +base_edge.h +/usr/local/include/g2o/core/base_edge.h +robust_kernel.h +/usr/local/include/g2o/core/robust_kernel.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +base_multi_edge.hpp +/usr/local/include/g2o/core/base_multi_edge.hpp + +/usr/local/include/g2o/core/base_multi_edge.hpp + +/usr/local/include/g2o/core/base_unary_edge.h +iostream +- +cassert +- +limits +- +base_edge.h +/usr/local/include/g2o/core/base_edge.h +robust_kernel.h +/usr/local/include/g2o/core/robust_kernel.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +base_unary_edge.hpp +/usr/local/include/g2o/core/base_unary_edge.hpp + +/usr/local/include/g2o/core/base_unary_edge.hpp + +/usr/local/include/g2o/core/base_vertex.h +optimizable_graph.h +/usr/local/include/g2o/core/optimizable_graph.h +creators.h +/usr/local/include/g2o/core/creators.h +g2o/stuff/macros.h +/usr/local/include/g2o/core/g2o/stuff/macros.h +Eigen/Core +- +Eigen/Dense +- +Eigen/Cholesky +- +Eigen/StdVector +- +stack +- +base_vertex.hpp +/usr/local/include/g2o/core/base_vertex.hpp + +/usr/local/include/g2o/core/base_vertex.hpp + +/usr/local/include/g2o/core/batch_stats.h +iostream +- +vector +- +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/block_solver.h +Eigen/Core +- +solver.h +/usr/local/include/g2o/core/solver.h +linear_solver.h +/usr/local/include/g2o/core/linear_solver.h +sparse_block_matrix.h +/usr/local/include/g2o/core/sparse_block_matrix.h +sparse_block_matrix_diagonal.h +/usr/local/include/g2o/core/sparse_block_matrix_diagonal.h +openmp_mutex.h +/usr/local/include/g2o/core/openmp_mutex.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +block_solver.hpp +/usr/local/include/g2o/core/block_solver.hpp + +/usr/local/include/g2o/core/block_solver.hpp +sparse_optimizer.h +/usr/local/include/g2o/core/sparse_optimizer.h +Eigen/LU +- +fstream +- +iomanip +- +g2o/stuff/timeutil.h +/usr/local/include/g2o/core/g2o/stuff/timeutil.h +g2o/stuff/macros.h +/usr/local/include/g2o/core/g2o/stuff/macros.h +g2o/stuff/misc.h +/usr/local/include/g2o/core/g2o/stuff/misc.h + +/usr/local/include/g2o/core/creators.h +hyper_graph.h +/usr/local/include/g2o/core/hyper_graph.h +string +- +typeinfo +- + +/usr/local/include/g2o/core/eigen_types.h +Eigen/Core +- +Eigen/Geometry +- + +/usr/local/include/g2o/core/g2o_core_api.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h + +/usr/local/include/g2o/core/hyper_graph.h +map +- +set +- +bitset +- +cassert +- +vector +- +limits +- +cstddef +- +unordered_map +- +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/jacobian_workspace.h +Eigen/Core +- +Eigen/StdVector +- +vector +- +cassert +- +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h +hyper_graph.h +/usr/local/include/g2o/core/hyper_graph.h + +/usr/local/include/g2o/core/linear_solver.h +sparse_block_matrix.h +/usr/local/include/g2o/core/sparse_block_matrix.h +sparse_block_matrix_ccs.h +/usr/local/include/g2o/core/sparse_block_matrix_ccs.h + +/usr/local/include/g2o/core/matrix_operations.h +Eigen/Core +- + +/usr/local/include/g2o/core/matrix_structure.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/openmp_mutex.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +omp.h +- +cassert +- + +/usr/local/include/g2o/core/optimizable_graph.h +set +- +iostream +- +list +- +limits +- +cmath +- +typeinfo +- +openmp_mutex.h +/usr/local/include/g2o/core/openmp_mutex.h +hyper_graph.h +/usr/local/include/g2o/core/hyper_graph.h +parameter.h +/usr/local/include/g2o/core/parameter.h +parameter_container.h +/usr/local/include/g2o/core/parameter_container.h +jacobian_workspace.h +/usr/local/include/g2o/core/jacobian_workspace.h +g2o/stuff/macros.h +/usr/local/include/g2o/core/g2o/stuff/macros.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/optimization_algorithm.h +vector +- +utility +- +iosfwd +- +g2o/stuff/property.h +/usr/local/include/g2o/core/g2o/stuff/property.h +hyper_graph.h +/usr/local/include/g2o/core/hyper_graph.h +sparse_block_matrix.h +/usr/local/include/g2o/core/sparse_block_matrix.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/optimization_algorithm_levenberg.h +optimization_algorithm_with_hessian.h +/usr/local/include/g2o/core/optimization_algorithm_with_hessian.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/optimization_algorithm_with_hessian.h +optimization_algorithm.h +/usr/local/include/g2o/core/optimization_algorithm.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/parameter.h +iosfwd +- +hyper_graph.h +/usr/local/include/g2o/core/hyper_graph.h + +/usr/local/include/g2o/core/parameter_container.h +iosfwd +- +map +- +string +- + +/usr/local/include/g2o/core/robust_kernel.h +memory +- +Eigen/Core +- +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/solver.h +hyper_graph.h +/usr/local/include/g2o/core/hyper_graph.h +batch_stats.h +/usr/local/include/g2o/core/batch_stats.h +sparse_block_matrix.h +/usr/local/include/g2o/core/sparse_block_matrix.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h +cstddef +- + +/usr/local/include/g2o/core/sparse_block_matrix.h +map +- +vector +- +fstream +- +iostream +- +iomanip +- +cassert +- +Eigen/Core +- +sparse_block_matrix_ccs.h +/usr/local/include/g2o/core/sparse_block_matrix_ccs.h +matrix_structure.h +/usr/local/include/g2o/core/matrix_structure.h +matrix_operations.h +/usr/local/include/g2o/core/matrix_operations.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +sparse_block_matrix.hpp +/usr/local/include/g2o/core/sparse_block_matrix.hpp + +/usr/local/include/g2o/core/sparse_block_matrix.hpp + +/usr/local/include/g2o/core/sparse_block_matrix_ccs.h +vector +- +cassert +- +Eigen/Core +- +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +matrix_operations.h +/usr/local/include/g2o/core/matrix_operations.h +unordered_map +- + +/usr/local/include/g2o/core/sparse_block_matrix_diagonal.h +vector +- +Eigen/Core +- +Eigen/StdVector +- +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +matrix_operations.h +/usr/local/include/g2o/core/matrix_operations.h + +/usr/local/include/g2o/core/sparse_optimizer.h +g2o/stuff/macros.h +/usr/local/include/g2o/core/g2o/stuff/macros.h +optimizable_graph.h +/usr/local/include/g2o/core/optimizable_graph.h +sparse_block_matrix.h +/usr/local/include/g2o/core/sparse_block_matrix.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h +batch_stats.h +/usr/local/include/g2o/core/batch_stats.h +map +- + +/usr/local/include/g2o/solvers/dense/linear_solver_dense.h +g2o/core/linear_solver.h +/usr/local/include/g2o/solvers/dense/g2o/core/linear_solver.h +g2o/core/batch_stats.h +/usr/local/include/g2o/solvers/dense/g2o/core/batch_stats.h +vector +- +utility +- +Eigen/Core +- +Eigen/Cholesky +- + +/usr/local/include/g2o/stuff/g2o_stuff_api.h +g2o/config.h +/usr/local/include/g2o/stuff/g2o/config.h + +/usr/local/include/g2o/stuff/macros.h +float.h +- +math.h +- + +/usr/local/include/g2o/stuff/misc.h +macros.h +/usr/local/include/g2o/stuff/macros.h +cmath +- + +/usr/local/include/g2o/stuff/property.h +string +- +map +- +sstream +- +string_tools.h +/usr/local/include/g2o/stuff/string_tools.h +g2o_stuff_api.h +/usr/local/include/g2o/stuff/g2o_stuff_api.h + +/usr/local/include/g2o/stuff/string_tools.h +string +- +sstream +- +cstdlib +- +vector +- +macros.h +/usr/local/include/g2o/stuff/macros.h +g2o_stuff_api.h +/usr/local/include/g2o/stuff/g2o_stuff_api.h + +/usr/local/include/g2o/stuff/timeutil.h +time.h +- +sys/time.h +- +string +- +g2o_stuff_api.h +/usr/local/include/g2o/stuff/g2o_stuff_api.h + +/usr/local/include/g2o/types/sba/g2o_types_sba_api.h +g2o/config.h +/usr/local/include/g2o/types/sba/g2o/config.h + +/usr/local/include/g2o/types/sba/sbacam.h +Eigen/Core +- +Eigen/Geometry +- +g2o/stuff/misc.h +/usr/local/include/g2o/types/sba/g2o/stuff/misc.h +g2o/stuff/macros.h +/usr/local/include/g2o/types/sba/g2o/stuff/macros.h +g2o/types/slam3d/se3quat.h +/usr/local/include/g2o/types/sba/g2o/types/slam3d/se3quat.h +g2o_types_sba_api.h +/usr/local/include/g2o/types/sba/g2o_types_sba_api.h + +/usr/local/include/g2o/types/sba/types_sba.h +g2o/core/base_vertex.h +/usr/local/include/g2o/types/sba/g2o/core/base_vertex.h +g2o/core/base_binary_edge.h +/usr/local/include/g2o/types/sba/g2o/core/base_binary_edge.h +g2o/core/base_multi_edge.h +/usr/local/include/g2o/types/sba/g2o/core/base_multi_edge.h +sbacam.h +/usr/local/include/g2o/types/sba/sbacam.h +Eigen/Geometry +- +iostream +- +g2o_types_sba_api.h +/usr/local/include/g2o/types/sba/g2o_types_sba_api.h + +/usr/local/include/g2o/types/sba/types_six_dof_expmap.h +g2o/core/base_vertex.h +/usr/local/include/g2o/types/sba/g2o/core/base_vertex.h +g2o/core/base_binary_edge.h +/usr/local/include/g2o/types/sba/g2o/core/base_binary_edge.h +g2o/types/slam3d/se3_ops.h +/usr/local/include/g2o/types/sba/g2o/types/slam3d/se3_ops.h +types_sba.h +/usr/local/include/g2o/types/sba/types_sba.h +Eigen/Geometry +- + +/usr/local/include/g2o/types/slam3d/g2o_types_slam3d_api.h +g2o/config.h +/usr/local/include/g2o/types/slam3d/g2o/config.h + +/usr/local/include/g2o/types/slam3d/se3_ops.h +Eigen/Core +- +Eigen/Geometry +- +g2o_types_slam3d_api.h +/usr/local/include/g2o/types/slam3d/g2o_types_slam3d_api.h +se3_ops.hpp +/usr/local/include/g2o/types/slam3d/se3_ops.hpp + +/usr/local/include/g2o/types/slam3d/se3_ops.hpp + +/usr/local/include/g2o/types/slam3d/se3quat.h +se3_ops.h +/usr/local/include/g2o/types/slam3d/se3_ops.h +Eigen/Core +- +Eigen/Geometry +- + +/usr/local/include/opencv/cxcore.h +opencv2/core/core_c.h +/usr/local/include/opencv/opencv2/core/core_c.h + +/usr/local/include/opencv2/calib3d.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/opencv2/features2d.hpp +opencv2/core/affine.hpp +/usr/local/include/opencv2/opencv2/core/affine.hpp +opencv2/calib3d/calib3d_c.h +/usr/local/include/opencv2/opencv2/calib3d/calib3d_c.h + +/usr/local/include/opencv2/calib3d/calib3d_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/calib3d/opencv2/core/core_c.h + +/usr/local/include/opencv2/core.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/opencv2/core/cvdef.h +opencv2/core/version.hpp +/usr/local/include/opencv2/opencv2/core/version.hpp +opencv2/core/base.hpp +/usr/local/include/opencv2/opencv2/core/base.hpp +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/opencv2/core/cvstd.hpp +opencv2/core/traits.hpp +/usr/local/include/opencv2/opencv2/core/traits.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/opencv2/core/matx.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/opencv2/core/types.hpp +opencv2/core/mat.hpp +/usr/local/include/opencv2/opencv2/core/mat.hpp +opencv2/core/persistence.hpp +/usr/local/include/opencv2/opencv2/core/persistence.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/opencv2/opencv.hpp +opencv2/xfeatures2d.hpp +/usr/local/include/opencv2/opencv2/xfeatures2d.hpp +opencv2/core/operations.hpp +/usr/local/include/opencv2/opencv2/core/operations.hpp +opencv2/core/cvstd.inl.hpp +/usr/local/include/opencv2/opencv2/core/cvstd.inl.hpp +opencv2/core/utility.hpp +/usr/local/include/opencv2/opencv2/core/utility.hpp +opencv2/core/optim.hpp +/usr/local/include/opencv2/opencv2/core/optim.hpp + +/usr/local/include/opencv2/core/affine.hpp +opencv2/core.hpp +- + +/usr/local/include/opencv2/core/base.hpp +climits +- +algorithm +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/core/opencv2/core/cvstd.hpp +opencv2/core/neon_utils.hpp +/usr/local/include/opencv2/core/opencv2/core/neon_utils.hpp + +/usr/local/include/opencv2/core/bufferpool.hpp + +/usr/local/include/opencv2/core/core.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/core_c.h +opencv2/core/types_c.h +/usr/local/include/opencv2/core/opencv2/core/types_c.h +cxcore.h +/usr/local/include/opencv2/core/cxcore.h +cxcore.h +/usr/local/include/opencv2/core/cxcore.h +opencv2/core/utility.hpp +/usr/local/include/opencv2/core/opencv2/core/utility.hpp + +/usr/local/include/opencv2/core/cvdef.h +limits.h +- +opencv2/core/hal/interface.h +/usr/local/include/opencv2/core/opencv2/core/hal/interface.h +emmintrin.h +- +pmmintrin.h +- +tmmintrin.h +- +smmintrin.h +- +nmmintrin.h +- +nmmintrin.h +- +popcntintrin.h +- +immintrin.h +- +immintrin.h +- +Intrin.h +- +arm_neon.h +/usr/local/include/opencv2/core/arm_neon.h +arm_neon.h +- +intrin.h +- + +/usr/local/include/opencv2/core/cvstd.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +cstddef +- +cstring +- +cctype +- +string +- +algorithm +- +utility +- +cstdlib +- +cmath +- +opencv2/core/ptr.inl.hpp +/usr/local/include/opencv2/core/opencv2/core/ptr.inl.hpp + +/usr/local/include/opencv2/core/cvstd.inl.hpp +complex +- +ostream +- + +/usr/local/include/opencv2/core/fast_math.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +fastmath.h +- +cmath +- +math.h +- +tegra_round.hpp +/usr/local/include/opencv2/core/tegra_round.hpp + +/usr/local/include/opencv2/core/hal/interface.h +cstddef +- +stddef.h +- +cstdint +- +stdint.h +- + +/usr/local/include/opencv2/core/mat.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/core/opencv2/core/matx.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/core/opencv2/core/types.hpp +opencv2/core/bufferpool.hpp +/usr/local/include/opencv2/core/opencv2/core/bufferpool.hpp +opencv2/core/mat.inl.hpp +/usr/local/include/opencv2/core/opencv2/core/mat.inl.hpp + +/usr/local/include/opencv2/core/mat.inl.hpp + +/usr/local/include/opencv2/core/matx.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/base.hpp +/usr/local/include/opencv2/core/opencv2/core/base.hpp +opencv2/core/traits.hpp +/usr/local/include/opencv2/core/opencv2/core/traits.hpp +opencv2/core/saturate.hpp +/usr/local/include/opencv2/core/opencv2/core/saturate.hpp + +/usr/local/include/opencv2/core/neon_utils.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h + +/usr/local/include/opencv2/core/operations.hpp +cstdio +- + +/usr/local/include/opencv2/core/optim.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/persistence.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/core/opencv2/core/types.hpp +opencv2/core/mat.hpp +/usr/local/include/opencv2/core/opencv2/core/mat.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/core/opencv2/opencv.hpp +time.h +- + +/usr/local/include/opencv2/core/ptr.inl.hpp +algorithm +- + +/usr/local/include/opencv2/core/saturate.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/fast_math.hpp +/usr/local/include/opencv2/core/opencv2/core/fast_math.hpp + +/usr/local/include/opencv2/core/traits.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h + +/usr/local/include/opencv2/core/types.hpp +climits +- +cfloat +- +vector +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/core/opencv2/core/cvstd.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/core/opencv2/core/matx.hpp + +/usr/local/include/opencv2/core/types_c.h +ipl.h +- +ipl/ipl.h +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +assert.h +- +stdlib.h +- +string.h +- +float.h +- +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/utility.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp +opencv2/core/core_c.h +/usr/local/include/opencv2/core/opencv2/core/core_c.h + +/usr/local/include/opencv2/core/version.hpp + +/usr/local/include/opencv2/features2d.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/flann/miniflann.hpp +/usr/local/include/opencv2/opencv2/flann/miniflann.hpp + +/usr/local/include/opencv2/features2d/features2d.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/features2d/opencv2/features2d.hpp + +/usr/local/include/opencv2/flann/config.h + +/usr/local/include/opencv2/flann/defines.h +config.h +/usr/local/include/opencv2/flann/config.h + +/usr/local/include/opencv2/flann/miniflann.hpp +opencv2/core.hpp +/usr/local/include/opencv2/flann/opencv2/core.hpp +opencv2/flann/defines.h +/usr/local/include/opencv2/flann/opencv2/flann/defines.h + +/usr/local/include/opencv2/highgui.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgcodecs.hpp +/usr/local/include/opencv2/opencv2/imgcodecs.hpp +opencv2/videoio.hpp +/usr/local/include/opencv2/opencv2/videoio.hpp +opencv2/highgui/highgui_c.h +/usr/local/include/opencv2/opencv2/highgui/highgui_c.h + +/usr/local/include/opencv2/highgui/highgui.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/highgui/opencv2/highgui.hpp + +/usr/local/include/opencv2/highgui/highgui_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/highgui/opencv2/core/core_c.h +opencv2/imgproc/imgproc_c.h +/usr/local/include/opencv2/highgui/opencv2/imgproc/imgproc_c.h +opencv2/imgcodecs/imgcodecs_c.h +/usr/local/include/opencv2/highgui/opencv2/imgcodecs/imgcodecs_c.h +opencv2/videoio/videoio_c.h +/usr/local/include/opencv2/highgui/opencv2/videoio/videoio_c.h + +/usr/local/include/opencv2/imgcodecs.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/opencv.hpp +- + +/usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/imgcodecs/opencv2/core/core_c.h + +/usr/local/include/opencv2/imgproc.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/core.hpp +- +opencv2/imgproc.hpp +- +opencv2/imgcodecs.hpp +- +opencv2/highgui.hpp +- +iostream +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +math.h +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/opencv2/highgui.hpp +opencv2/imgproc/imgproc_c.h +/usr/local/include/opencv2/opencv2/imgproc/imgproc_c.h + +/usr/local/include/opencv2/imgproc/imgproc.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/imgproc/opencv2/imgproc.hpp + +/usr/local/include/opencv2/imgproc/imgproc_c.h +opencv2/imgproc/types_c.h +/usr/local/include/opencv2/imgproc/opencv2/imgproc/types_c.h + +/usr/local/include/opencv2/imgproc/types_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/imgproc/opencv2/core/core_c.h + +/usr/local/include/opencv2/ml.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +float.h +- +map +- +iostream +- + +/usr/local/include/opencv2/objdetect.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/objdetect/detection_based_tracker.hpp +/usr/local/include/opencv2/opencv2/objdetect/detection_based_tracker.hpp +opencv2/objdetect/objdetect_c.h +/usr/local/include/opencv2/opencv2/objdetect/objdetect_c.h + +/usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +vector +- + +/usr/local/include/opencv2/objdetect/objdetect_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/objdetect/opencv2/core/core_c.h +deque +- +vector +- + +/usr/local/include/opencv2/opencv.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/photo.hpp +/usr/local/include/opencv2/opencv2/photo.hpp +opencv2/video.hpp +/usr/local/include/opencv2/opencv2/video.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/opencv2/features2d.hpp +opencv2/objdetect.hpp +/usr/local/include/opencv2/opencv2/objdetect.hpp +opencv2/calib3d.hpp +/usr/local/include/opencv2/opencv2/calib3d.hpp +opencv2/imgcodecs.hpp +/usr/local/include/opencv2/opencv2/imgcodecs.hpp +opencv2/videoio.hpp +/usr/local/include/opencv2/opencv2/videoio.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/opencv2/highgui.hpp +opencv2/ml.hpp +/usr/local/include/opencv2/opencv2/ml.hpp + +/usr/local/include/opencv2/photo.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/photo/photo_c.h +/usr/local/include/opencv2/opencv2/photo/photo_c.h + +/usr/local/include/opencv2/photo/photo_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/photo/opencv2/core/core_c.h + +/usr/local/include/opencv2/video.hpp +opencv2/video/tracking.hpp +/usr/local/include/opencv2/opencv2/video/tracking.hpp +opencv2/video/background_segm.hpp +/usr/local/include/opencv2/opencv2/video/background_segm.hpp +opencv2/video/tracking_c.h +/usr/local/include/opencv2/opencv2/video/tracking_c.h + +/usr/local/include/opencv2/video/background_segm.hpp +opencv2/core.hpp +/usr/local/include/opencv2/video/opencv2/core.hpp + +/usr/local/include/opencv2/video/tracking.hpp +opencv2/core.hpp +/usr/local/include/opencv2/video/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/video/opencv2/imgproc.hpp + +/usr/local/include/opencv2/video/tracking_c.h +opencv2/imgproc/types_c.h +/usr/local/include/opencv2/video/opencv2/imgproc/types_c.h + +/usr/local/include/opencv2/videoio.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/opencv2/opencv.hpp + +/usr/local/include/opencv2/videoio/videoio_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/videoio/opencv2/core/core_c.h + diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/DependInfo.cmake b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/DependInfo.cmake new file mode 100644 index 00000000..75a4a014 --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/DependInfo.cmake @@ -0,0 +1,23 @@ +# The set of languages for which implicit dependencies are needed: +SET(CMAKE_DEPENDS_LANGUAGES + "CXX" + ) +# The set of files for implicit dependencies of each language: +SET(CMAKE_DEPENDS_CHECK_CXX + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/direct_sparse.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o" + ) +SET(CMAKE_CXX_COMPILER_ID "GNU") + +# Targets to which this target links. +SET(CMAKE_TARGET_LINKED_INFO_FILES + ) + +# The include file search paths: +SET(CMAKE_C_TARGET_INCLUDE_PATH + "/usr/local/include/opencv" + "/usr/local/include" + "/usr/include/eigen3" + ) +SET(CMAKE_CXX_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) +SET(CMAKE_Fortran_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) +SET(CMAKE_ASM_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/build.make b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/build.make new file mode 100644 index 00000000..61b4a17d --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/build.make @@ -0,0 +1,128 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build + +# Include any dependencies generated for this target. +include CMakeFiles/direct_sparse.dir/depend.make + +# Include the progress variables for this target. +include CMakeFiles/direct_sparse.dir/progress.make + +# Include the compile flags for this target's objects. +include CMakeFiles/direct_sparse.dir/flags.make + +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: CMakeFiles/direct_sparse.dir/flags.make +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: ../direct_sparse.cpp + $(CMAKE_COMMAND) -E cmake_progress_report /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles $(CMAKE_PROGRESS_1) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o" + /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o -c /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/direct_sparse.cpp + +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/direct_sparse.dir/direct_sparse.cpp.i" + /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -E /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/direct_sparse.cpp > CMakeFiles/direct_sparse.dir/direct_sparse.cpp.i + +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/direct_sparse.dir/direct_sparse.cpp.s" + /usr/bin/c++ $(CXX_DEFINES) $(CXX_FLAGS) -S /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/direct_sparse.cpp -o CMakeFiles/direct_sparse.dir/direct_sparse.cpp.s + +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o.requires: +.PHONY : CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o.requires + +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o.provides: CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o.requires + $(MAKE) -f CMakeFiles/direct_sparse.dir/build.make CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o.provides.build +.PHONY : CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o.provides + +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o.provides.build: CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o + +# Object files for target direct_sparse +direct_sparse_OBJECTS = \ +"CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o" + +# External object files for target direct_sparse +direct_sparse_EXTERNAL_OBJECTS = + +direct_sparse: CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o +direct_sparse: CMakeFiles/direct_sparse.dir/build.make +direct_sparse: /usr/local/lib/libopencv_viz.so.3.1.0 +direct_sparse: /usr/local/lib/libopencv_videostab.so.3.1.0 +direct_sparse: /usr/local/lib/libopencv_videoio.so.3.1.0 +direct_sparse: /usr/local/lib/libopencv_video.so.3.1.0 +direct_sparse: /usr/local/lib/libopencv_superres.so.3.1.0 +direct_sparse: /usr/local/lib/libopencv_stitching.so.3.1.0 +direct_sparse: /usr/local/lib/libopencv_shape.so.3.1.0 +direct_sparse: /usr/local/lib/libopencv_photo.so.3.1.0 +direct_sparse: /usr/local/lib/libopencv_objdetect.so.3.1.0 +direct_sparse: /usr/local/lib/libopencv_ml.so.3.1.0 +direct_sparse: /usr/local/lib/libopencv_imgproc.so.3.1.0 +direct_sparse: /usr/local/lib/libopencv_imgcodecs.so.3.1.0 +direct_sparse: /usr/local/lib/libopencv_highgui.so.3.1.0 +direct_sparse: /usr/local/lib/libopencv_flann.so.3.1.0 +direct_sparse: /usr/local/lib/libopencv_features2d.so.3.1.0 +direct_sparse: /usr/local/lib/libopencv_core.so.3.1.0 +direct_sparse: /usr/local/lib/libopencv_calib3d.so.3.1.0 +direct_sparse: /usr/local/lib/libopencv_features2d.so.3.1.0 +direct_sparse: /usr/local/lib/libopencv_ml.so.3.1.0 +direct_sparse: /usr/local/lib/libopencv_highgui.so.3.1.0 +direct_sparse: /usr/local/lib/libopencv_videoio.so.3.1.0 +direct_sparse: /usr/local/lib/libopencv_imgcodecs.so.3.1.0 +direct_sparse: /usr/local/lib/libopencv_flann.so.3.1.0 +direct_sparse: /usr/local/lib/libopencv_video.so.3.1.0 +direct_sparse: /usr/local/lib/libopencv_imgproc.so.3.1.0 +direct_sparse: /usr/local/lib/libopencv_core.so.3.1.0 +direct_sparse: CMakeFiles/direct_sparse.dir/link.txt + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --red --bold "Linking CXX executable direct_sparse" + $(CMAKE_COMMAND) -E cmake_link_script CMakeFiles/direct_sparse.dir/link.txt --verbose=$(VERBOSE) + +# Rule to build all files generated by this target. +CMakeFiles/direct_sparse.dir/build: direct_sparse +.PHONY : CMakeFiles/direct_sparse.dir/build + +CMakeFiles/direct_sparse.dir/requires: CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o.requires +.PHONY : CMakeFiles/direct_sparse.dir/requires + +CMakeFiles/direct_sparse.dir/clean: + $(CMAKE_COMMAND) -P CMakeFiles/direct_sparse.dir/cmake_clean.cmake +.PHONY : CMakeFiles/direct_sparse.dir/clean + +CMakeFiles/direct_sparse.dir/depend: + cd /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/DependInfo.cmake --color=$(COLOR) +.PHONY : CMakeFiles/direct_sparse.dir/depend + diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/cmake_clean.cmake b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/cmake_clean.cmake new file mode 100644 index 00000000..3dd300d3 --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/cmake_clean.cmake @@ -0,0 +1,10 @@ +FILE(REMOVE_RECURSE + "CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o" + "direct_sparse.pdb" + "direct_sparse" +) + +# Per-language clean rules from dependency scanning. +FOREACH(lang CXX) + INCLUDE(CMakeFiles/direct_sparse.dir/cmake_clean_${lang}.cmake OPTIONAL) +ENDFOREACH(lang) diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/depend.internal b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/depend.internal new file mode 100644 index 00000000..deeff50d --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/depend.internal @@ -0,0 +1,315 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/direct_sparse.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Dense + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/g2o/config.h + /usr/local/include/g2o/core/base_binary_edge.h + /usr/local/include/g2o/core/base_binary_edge.hpp + /usr/local/include/g2o/core/base_edge.h + /usr/local/include/g2o/core/base_multi_edge.h + /usr/local/include/g2o/core/base_multi_edge.hpp + /usr/local/include/g2o/core/base_unary_edge.h + /usr/local/include/g2o/core/base_unary_edge.hpp + /usr/local/include/g2o/core/base_vertex.h + /usr/local/include/g2o/core/base_vertex.hpp + /usr/local/include/g2o/core/batch_stats.h + /usr/local/include/g2o/core/block_solver.h + /usr/local/include/g2o/core/block_solver.hpp + /usr/local/include/g2o/core/creators.h + /usr/local/include/g2o/core/eigen_types.h + /usr/local/include/g2o/core/g2o_core_api.h + /usr/local/include/g2o/core/hyper_graph.h + /usr/local/include/g2o/core/jacobian_workspace.h + /usr/local/include/g2o/core/linear_solver.h + /usr/local/include/g2o/core/matrix_operations.h + /usr/local/include/g2o/core/matrix_structure.h + /usr/local/include/g2o/core/openmp_mutex.h + /usr/local/include/g2o/core/optimizable_graph.h + /usr/local/include/g2o/core/optimization_algorithm.h + /usr/local/include/g2o/core/optimization_algorithm_levenberg.h + /usr/local/include/g2o/core/optimization_algorithm_with_hessian.h + /usr/local/include/g2o/core/parameter.h + /usr/local/include/g2o/core/parameter_container.h + /usr/local/include/g2o/core/robust_kernel.h + /usr/local/include/g2o/core/solver.h + /usr/local/include/g2o/core/sparse_block_matrix.h + /usr/local/include/g2o/core/sparse_block_matrix.hpp + /usr/local/include/g2o/core/sparse_block_matrix_ccs.h + /usr/local/include/g2o/core/sparse_block_matrix_diagonal.h + /usr/local/include/g2o/core/sparse_optimizer.h + /usr/local/include/g2o/solvers/dense/linear_solver_dense.h + /usr/local/include/g2o/stuff/g2o_stuff_api.h + /usr/local/include/g2o/stuff/macros.h + /usr/local/include/g2o/stuff/misc.h + /usr/local/include/g2o/stuff/property.h + /usr/local/include/g2o/stuff/string_tools.h + /usr/local/include/g2o/stuff/timeutil.h + /usr/local/include/g2o/types/sba/g2o_types_sba_api.h + /usr/local/include/g2o/types/sba/sbacam.h + /usr/local/include/g2o/types/sba/types_sba.h + /usr/local/include/g2o/types/sba/types_six_dof_expmap.h + /usr/local/include/g2o/types/slam3d/g2o_types_slam3d_api.h + /usr/local/include/g2o/types/slam3d/se3_ops.h + /usr/local/include/g2o/types/slam3d/se3_ops.hpp + /usr/local/include/g2o/types/slam3d/se3quat.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/features2d/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/depend.make b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/depend.make new file mode 100644 index 00000000..4f8ce5db --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/depend.make @@ -0,0 +1,315 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: ../direct_sparse.cpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/Cholesky +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/Core +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/Dense +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/Geometry +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/Householder +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/Jacobi +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/LU +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/QR +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/SVD +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/StdVector +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/config.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/base_binary_edge.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/base_binary_edge.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/base_edge.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/base_multi_edge.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/base_multi_edge.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/base_unary_edge.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/base_unary_edge.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/base_vertex.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/base_vertex.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/batch_stats.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/block_solver.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/block_solver.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/creators.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/eigen_types.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/g2o_core_api.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/hyper_graph.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/jacobian_workspace.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/linear_solver.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/matrix_operations.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/matrix_structure.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/openmp_mutex.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/optimizable_graph.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/optimization_algorithm.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/optimization_algorithm_levenberg.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/optimization_algorithm_with_hessian.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/parameter.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/parameter_container.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/robust_kernel.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/solver.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/sparse_block_matrix.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/sparse_block_matrix.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/sparse_block_matrix_ccs.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/sparse_block_matrix_diagonal.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/core/sparse_optimizer.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/solvers/dense/linear_solver_dense.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/stuff/g2o_stuff_api.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/stuff/macros.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/stuff/misc.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/stuff/property.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/stuff/string_tools.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/stuff/timeutil.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/types/sba/g2o_types_sba_api.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/types/sba/sbacam.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/types/sba/types_sba.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/types/sba/types_six_dof_expmap.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/types/slam3d/g2o_types_slam3d_api.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/types/slam3d/se3_ops.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/types/slam3d/se3_ops.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/g2o/types/slam3d/se3quat.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv/cxcore.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/calib3d.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/core.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/core/affine.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/core/base.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/core/core.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/core/core_c.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/core/cvdef.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/core/mat.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/core/matx.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/core/operations.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/core/optim.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/core/traits.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/core/types.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/core/types_c.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/core/utility.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/core/version.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/features2d.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/features2d/features2d.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/flann/config.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/flann/defines.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/highgui.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/highgui/highgui.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/imgproc.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/imgproc/imgproc.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/ml.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/objdetect.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/opencv.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/photo.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/video.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/videoio.hpp +CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o new file mode 100644 index 00000000..0283ce4d Binary files /dev/null and b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o differ diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/flags.make b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/flags.make new file mode 100644 index 00000000..a8bf41a6 --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/flags.make @@ -0,0 +1,8 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# compile CXX with /usr/bin/c++ +CXX_FLAGS = -std=c++11 -O3 -O3 -DNDEBUG -I/usr/local/include/opencv -I/usr/local/include -I/usr/include/eigen3 + +CXX_DEFINES = + diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/link.txt b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/link.txt new file mode 100644 index 00000000..8afeb0d4 --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/link.txt @@ -0,0 +1 @@ +/usr/bin/c++ -std=c++11 -O3 -O3 -DNDEBUG CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o -o direct_sparse -rdynamic /usr/local/lib/libopencv_viz.so.3.1.0 /usr/local/lib/libopencv_videostab.so.3.1.0 /usr/local/lib/libopencv_videoio.so.3.1.0 /usr/local/lib/libopencv_video.so.3.1.0 /usr/local/lib/libopencv_superres.so.3.1.0 /usr/local/lib/libopencv_stitching.so.3.1.0 /usr/local/lib/libopencv_shape.so.3.1.0 /usr/local/lib/libopencv_photo.so.3.1.0 /usr/local/lib/libopencv_objdetect.so.3.1.0 /usr/local/lib/libopencv_ml.so.3.1.0 /usr/local/lib/libopencv_imgproc.so.3.1.0 /usr/local/lib/libopencv_imgcodecs.so.3.1.0 /usr/local/lib/libopencv_highgui.so.3.1.0 /usr/local/lib/libopencv_flann.so.3.1.0 /usr/local/lib/libopencv_features2d.so.3.1.0 /usr/local/lib/libopencv_core.so.3.1.0 /usr/local/lib/libopencv_calib3d.so.3.1.0 -lg2o_core -lg2o_types_sba -lg2o_solver_csparse -lg2o_stuff -lg2o_csparse_extension /usr/local/lib/libopencv_features2d.so.3.1.0 /usr/local/lib/libopencv_ml.so.3.1.0 /usr/local/lib/libopencv_highgui.so.3.1.0 /usr/local/lib/libopencv_videoio.so.3.1.0 /usr/local/lib/libopencv_imgcodecs.so.3.1.0 /usr/local/lib/libopencv_flann.so.3.1.0 /usr/local/lib/libopencv_video.so.3.1.0 /usr/local/lib/libopencv_imgproc.so.3.1.0 /usr/local/lib/libopencv_core.so.3.1.0 -Wl,-rpath,/usr/local/lib diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/progress.make b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/progress.make new file mode 100644 index 00000000..164e1d26 --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/direct_sparse.dir/progress.make @@ -0,0 +1,2 @@ +CMAKE_PROGRESS_1 = 2 + diff --git a/vSLAM/ch8/directMethod/build/CMakeFiles/progress.marks b/vSLAM/ch8/directMethod/build/CMakeFiles/progress.marks new file mode 100644 index 00000000..0cfbf088 --- /dev/null +++ b/vSLAM/ch8/directMethod/build/CMakeFiles/progress.marks @@ -0,0 +1 @@ +2 diff --git a/vSLAM/ch8/directMethod/build/Makefile b/vSLAM/ch8/directMethod/build/Makefile new file mode 100644 index 00000000..9c677d76 --- /dev/null +++ b/vSLAM/ch8/directMethod/build/Makefile @@ -0,0 +1,204 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Default target executed when no arguments are given to make. +default_target: all +.PHONY : default_target + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build + +#============================================================================= +# Targets provided globally by CMake. + +# Special rule for the target edit_cache +edit_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running interactive CMake command-line interface..." + /usr/bin/cmake -i . +.PHONY : edit_cache + +# Special rule for the target edit_cache +edit_cache/fast: edit_cache +.PHONY : edit_cache/fast + +# Special rule for the target rebuild_cache +rebuild_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake to regenerate build system..." + /usr/bin/cmake -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) +.PHONY : rebuild_cache + +# Special rule for the target rebuild_cache +rebuild_cache/fast: rebuild_cache +.PHONY : rebuild_cache/fast + +# The main all target +all: cmake_check_build_system + $(CMAKE_COMMAND) -E cmake_progress_start /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles/progress.marks + $(MAKE) -f CMakeFiles/Makefile2 all + $(CMAKE_COMMAND) -E cmake_progress_start /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/CMakeFiles 0 +.PHONY : all + +# The main clean target +clean: + $(MAKE) -f CMakeFiles/Makefile2 clean +.PHONY : clean + +# The main clean target +clean/fast: clean +.PHONY : clean/fast + +# Prepare targets for installation. +preinstall: all + $(MAKE) -f CMakeFiles/Makefile2 preinstall +.PHONY : preinstall + +# Prepare targets for installation. +preinstall/fast: + $(MAKE) -f CMakeFiles/Makefile2 preinstall +.PHONY : preinstall/fast + +# clear depends +depend: + $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 1 +.PHONY : depend + +#============================================================================= +# Target rules for targets named direct_semidense + +# Build rule for target. +direct_semidense: cmake_check_build_system + $(MAKE) -f CMakeFiles/Makefile2 direct_semidense +.PHONY : direct_semidense + +# fast build rule for target. +direct_semidense/fast: + $(MAKE) -f CMakeFiles/direct_semidense.dir/build.make CMakeFiles/direct_semidense.dir/build +.PHONY : direct_semidense/fast + +#============================================================================= +# Target rules for targets named direct_sparse + +# Build rule for target. +direct_sparse: cmake_check_build_system + $(MAKE) -f CMakeFiles/Makefile2 direct_sparse +.PHONY : direct_sparse + +# fast build rule for target. +direct_sparse/fast: + $(MAKE) -f CMakeFiles/direct_sparse.dir/build.make CMakeFiles/direct_sparse.dir/build +.PHONY : direct_sparse/fast + +direct_semidense.o: direct_semidense.cpp.o +.PHONY : direct_semidense.o + +# target to build an object file +direct_semidense.cpp.o: + $(MAKE) -f CMakeFiles/direct_semidense.dir/build.make CMakeFiles/direct_semidense.dir/direct_semidense.cpp.o +.PHONY : direct_semidense.cpp.o + +direct_semidense.i: direct_semidense.cpp.i +.PHONY : direct_semidense.i + +# target to preprocess a source file +direct_semidense.cpp.i: + $(MAKE) -f CMakeFiles/direct_semidense.dir/build.make CMakeFiles/direct_semidense.dir/direct_semidense.cpp.i +.PHONY : direct_semidense.cpp.i + +direct_semidense.s: direct_semidense.cpp.s +.PHONY : direct_semidense.s + +# target to generate assembly for a file +direct_semidense.cpp.s: + $(MAKE) -f CMakeFiles/direct_semidense.dir/build.make CMakeFiles/direct_semidense.dir/direct_semidense.cpp.s +.PHONY : direct_semidense.cpp.s + +direct_sparse.o: direct_sparse.cpp.o +.PHONY : direct_sparse.o + +# target to build an object file +direct_sparse.cpp.o: + $(MAKE) -f CMakeFiles/direct_sparse.dir/build.make CMakeFiles/direct_sparse.dir/direct_sparse.cpp.o +.PHONY : direct_sparse.cpp.o + +direct_sparse.i: direct_sparse.cpp.i +.PHONY : direct_sparse.i + +# target to preprocess a source file +direct_sparse.cpp.i: + $(MAKE) -f CMakeFiles/direct_sparse.dir/build.make CMakeFiles/direct_sparse.dir/direct_sparse.cpp.i +.PHONY : direct_sparse.cpp.i + +direct_sparse.s: direct_sparse.cpp.s +.PHONY : direct_sparse.s + +# target to generate assembly for a file +direct_sparse.cpp.s: + $(MAKE) -f CMakeFiles/direct_sparse.dir/build.make CMakeFiles/direct_sparse.dir/direct_sparse.cpp.s +.PHONY : direct_sparse.cpp.s + +# Help Target +help: + @echo "The following are some of the valid targets for this Makefile:" + @echo "... all (the default if no target is provided)" + @echo "... clean" + @echo "... depend" + @echo "... direct_semidense" + @echo "... direct_sparse" + @echo "... edit_cache" + @echo "... rebuild_cache" + @echo "... direct_semidense.o" + @echo "... direct_semidense.i" + @echo "... direct_semidense.s" + @echo "... direct_sparse.o" + @echo "... direct_sparse.i" + @echo "... direct_sparse.s" +.PHONY : help + + + +#============================================================================= +# Special targets to cleanup operation of make. + +# Special rule to run CMake to check the build system integrity. +# No rule that depends on this can have commands that come from listfiles +# because they might be regenerated. +cmake_check_build_system: + $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0 +.PHONY : cmake_check_build_system + diff --git a/vSLAM/ch8/directMethod/build/cmake_install.cmake b/vSLAM/ch8/directMethod/build/cmake_install.cmake new file mode 100644 index 00000000..f9f76c53 --- /dev/null +++ b/vSLAM/ch8/directMethod/build/cmake_install.cmake @@ -0,0 +1,44 @@ +# Install script for directory: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod + +# Set the install prefix +IF(NOT DEFINED CMAKE_INSTALL_PREFIX) + SET(CMAKE_INSTALL_PREFIX "/usr/local") +ENDIF(NOT DEFINED CMAKE_INSTALL_PREFIX) +STRING(REGEX REPLACE "/$" "" CMAKE_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}") + +# Set the install configuration name. +IF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + IF(BUILD_TYPE) + STRING(REGEX REPLACE "^[^A-Za-z0-9_]+" "" + CMAKE_INSTALL_CONFIG_NAME "${BUILD_TYPE}") + ELSE(BUILD_TYPE) + SET(CMAKE_INSTALL_CONFIG_NAME "Release") + ENDIF(BUILD_TYPE) + MESSAGE(STATUS "Install configuration: \"${CMAKE_INSTALL_CONFIG_NAME}\"") +ENDIF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + +# Set the component getting installed. +IF(NOT CMAKE_INSTALL_COMPONENT) + IF(COMPONENT) + MESSAGE(STATUS "Install component: \"${COMPONENT}\"") + SET(CMAKE_INSTALL_COMPONENT "${COMPONENT}") + ELSE(COMPONENT) + SET(CMAKE_INSTALL_COMPONENT) + ENDIF(COMPONENT) +ENDIF(NOT CMAKE_INSTALL_COMPONENT) + +# Install shared libraries without execute permission? +IF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + SET(CMAKE_INSTALL_SO_NO_EXE "1") +ENDIF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + +IF(CMAKE_INSTALL_COMPONENT) + SET(CMAKE_INSTALL_MANIFEST "install_manifest_${CMAKE_INSTALL_COMPONENT}.txt") +ELSE(CMAKE_INSTALL_COMPONENT) + SET(CMAKE_INSTALL_MANIFEST "install_manifest.txt") +ENDIF(CMAKE_INSTALL_COMPONENT) + +FILE(WRITE "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/${CMAKE_INSTALL_MANIFEST}" "") +FOREACH(file ${CMAKE_INSTALL_MANIFEST_FILES}) + FILE(APPEND "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/directMethod/build/${CMAKE_INSTALL_MANIFEST}" "${file}\n") +ENDFOREACH(file) diff --git a/vSLAM/ch8/directMethod/build/direct_semidense b/vSLAM/ch8/directMethod/build/direct_semidense new file mode 100755 index 00000000..bf04d1b2 Binary files /dev/null and b/vSLAM/ch8/directMethod/build/direct_semidense differ diff --git a/vSLAM/ch8/directMethod/build/direct_sparse b/vSLAM/ch8/directMethod/build/direct_sparse new file mode 100755 index 00000000..3dbb8308 Binary files /dev/null and b/vSLAM/ch8/directMethod/build/direct_sparse differ diff --git a/vSLAM/ch8/directMethod/directMethod.kdev4 b/vSLAM/ch8/directMethod/directMethod.kdev4 new file mode 100644 index 00000000..c713bef3 --- /dev/null +++ b/vSLAM/ch8/directMethod/directMethod.kdev4 @@ -0,0 +1,3 @@ +[Project] +Manager=KDevCMakeManager +Name=directMethod diff --git a/vSLAM/ch8/directMethod/direct_semidense.cpp b/vSLAM/ch8/directMethod/direct_semidense.cpp index e37ea3b8..7952409c 100644 --- a/vSLAM/ch8/directMethod/direct_semidense.cpp +++ b/vSLAM/ch8/directMethod/direct_semidense.cpp @@ -1,3 +1,7 @@ +/* + * 半稠密直接法 求相机位姿 + * ./direct_sparse ../../data/ + */ #include #include #include @@ -53,7 +57,7 @@ inline Eigen::Vector2d project3Dto2D ( float x, float y, float z, float fx, floa // 返回:true为成功,false失败 bool poseEstimationDirect ( const vector& measurements, cv::Mat* gray, Eigen::Matrix3f& intrinsics, Eigen::Isometry3d& Tcw ); - +//g20图优化 // project a 3d point into an image plane, the error is photometric error // an unary edge with one vertex SE3Expmap (the pose of camera) class EdgeSE3ProjectDirect: public BaseUnaryEdge< 1, double, VertexSE3Expmap> @@ -66,7 +70,7 @@ class EdgeSE3ProjectDirect: public BaseUnaryEdge< 1, double, VertexSE3Expmap> EdgeSE3ProjectDirect ( Eigen::Vector3d point, float fx, float fy, float cx, float cy, cv::Mat* image ) : x_world_ ( point ), fx_ ( fx ), fy_ ( fy ), cx_ ( cx ), cy_ ( cy ), image_ ( image ) {} - +//计算误差 virtual void computeError() { const VertexSE3Expmap* v =static_cast ( _vertices[0] ); @@ -84,7 +88,7 @@ class EdgeSE3ProjectDirect: public BaseUnaryEdge< 1, double, VertexSE3Expmap> _error ( 0,0 ) = getPixelValue ( x,y ) - _measurement; } } - +//求雅克比矩阵 // plus in manifold virtual void linearizeOplus( ) { @@ -158,7 +162,7 @@ int main ( int argc, char** argv ) { if ( argc != 2 ) { - cout<<"usage: useLK path_to_dataset"< measurements; // 相机内参 @@ -179,7 +185,7 @@ int main ( int argc, char** argv ) Eigen::Matrix3f K; K< keypoints; @@ -221,7 +227,7 @@ int main ( int argc, char** argv ) cout<<"direct method costs time: "<>24 & 0x00FF) +# define COMPILER_VERSION_MINOR HEX(__CODEGEARC_VERSION__>>16 & 0x00FF) +# define COMPILER_VERSION_PATCH HEX(__CODEGEARC_VERSION__ & 0xFFFF) + +#elif defined(__BORLANDC__) +# define COMPILER_ID "Borland" + /* __BORLANDC__ = 0xVRR */ +# define COMPILER_VERSION_MAJOR HEX(__BORLANDC__>>8) +# define COMPILER_VERSION_MINOR HEX(__BORLANDC__ & 0xFF) + +#elif defined(__WATCOMC__) +# define COMPILER_ID "Watcom" + /* __WATCOMC__ = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(__WATCOMC__ / 100) +# define COMPILER_VERSION_MINOR DEC(__WATCOMC__ % 100) + +#elif defined(__SUNPRO_C) +# define COMPILER_ID "SunPro" +# if __SUNPRO_C >= 0x5100 + /* __SUNPRO_C = 0xVRRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_C>>12) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_C>>4 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_C & 0xF) +# else + /* __SUNPRO_C = 0xVRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_C>>8) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_C>>4 & 0xF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_C & 0xF) +# endif + +#elif defined(__HP_cc) +# define COMPILER_ID "HP" + /* __HP_cc = VVRRPP */ +# define COMPILER_VERSION_MAJOR DEC(__HP_cc/10000) +# define COMPILER_VERSION_MINOR DEC(__HP_cc/100 % 100) +# define COMPILER_VERSION_PATCH DEC(__HP_cc % 100) + +#elif defined(__DECC) +# define COMPILER_ID "Compaq" + /* __DECC_VER = VVRRTPPPP */ +# define COMPILER_VERSION_MAJOR DEC(__DECC_VER/10000000) +# define COMPILER_VERSION_MINOR DEC(__DECC_VER/100000 % 100) +# define COMPILER_VERSION_PATCH DEC(__DECC_VER % 10000) + +#elif defined(__IBMC__) +# if defined(__COMPILER_VER__) +# define COMPILER_ID "zOS" +# else +# if __IBMC__ >= 800 +# define COMPILER_ID "XL" +# else +# define COMPILER_ID "VisualAge" +# endif + /* __IBMC__ = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__IBMC__/100) +# define COMPILER_VERSION_MINOR DEC(__IBMC__/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__IBMC__ % 10) +# endif + +#elif defined(__PGI) +# define COMPILER_ID "PGI" +# define COMPILER_VERSION_MAJOR DEC(__PGIC__) +# define COMPILER_VERSION_MINOR DEC(__PGIC_MINOR__) +# if defined(__PGIC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__PGIC_PATCHLEVEL__) +# endif + +#elif defined(_CRAYC) +# define COMPILER_ID "Cray" +# define COMPILER_VERSION_MAJOR DEC(_RELEASE) +# define COMPILER_VERSION_MINOR DEC(_RELEASE_MINOR) + +#elif defined(__TI_COMPILER_VERSION__) +# define COMPILER_ID "TI" + /* __TI_COMPILER_VERSION__ = VVVRRRPPP */ +# define COMPILER_VERSION_MAJOR DEC(__TI_COMPILER_VERSION__/1000000) +# define COMPILER_VERSION_MINOR DEC(__TI_COMPILER_VERSION__/1000 % 1000) +# define COMPILER_VERSION_PATCH DEC(__TI_COMPILER_VERSION__ % 1000) + +#elif defined(__TINYC__) +# define COMPILER_ID "TinyCC" + +#elif defined(__SCO_VERSION__) +# define COMPILER_ID "SCO" + +#elif defined(__GNUC__) +# define COMPILER_ID "GNU" +# define COMPILER_VERSION_MAJOR DEC(__GNUC__) +# define COMPILER_VERSION_MINOR DEC(__GNUC_MINOR__) +# if defined(__GNUC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__) +# endif + +#elif defined(_MSC_VER) +# define COMPILER_ID "MSVC" + /* _MSC_VER = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(_MSC_VER / 100) +# define COMPILER_VERSION_MINOR DEC(_MSC_VER % 100) +# if defined(_MSC_FULL_VER) +# if _MSC_VER >= 1400 + /* _MSC_FULL_VER = VVRRPPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 100000) +# else + /* _MSC_FULL_VER = VVRRPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 10000) +# endif +# endif +# if defined(_MSC_BUILD) +# define COMPILER_VERSION_TWEAK DEC(_MSC_BUILD) +# endif + +/* Analog VisualDSP++ >= 4.5.6 */ +#elif defined(__VISUALDSPVERSION__) +# define COMPILER_ID "ADSP" + /* __VISUALDSPVERSION__ = 0xVVRRPP00 */ +# define COMPILER_VERSION_MAJOR HEX(__VISUALDSPVERSION__>>24) +# define COMPILER_VERSION_MINOR HEX(__VISUALDSPVERSION__>>16 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__VISUALDSPVERSION__>>8 & 0xFF) + +/* Analog VisualDSP++ < 4.5.6 */ +#elif defined(__ADSPBLACKFIN__) || defined(__ADSPTS__) || defined(__ADSP21000__) +# define COMPILER_ID "ADSP" + +/* IAR Systems compiler for embedded systems. + http://www.iar.com */ +#elif defined(__IAR_SYSTEMS_ICC__ ) || defined(__IAR_SYSTEMS_ICC) +# define COMPILER_ID "IAR" + +/* sdcc, the small devices C compiler for embedded systems, + http://sdcc.sourceforge.net */ +#elif defined(SDCC) +# define COMPILER_ID "SDCC" + /* SDCC = VRP */ +# define COMPILER_VERSION_MAJOR DEC(SDCC/100) +# define COMPILER_VERSION_MINOR DEC(SDCC/10 % 10) +# define COMPILER_VERSION_PATCH DEC(SDCC % 10) + +#elif defined(_SGI_COMPILER_VERSION) || defined(_COMPILER_VERSION) +# define COMPILER_ID "MIPSpro" +# if defined(_SGI_COMPILER_VERSION) + /* _SGI_COMPILER_VERSION = VRP */ +# define COMPILER_VERSION_MAJOR DEC(_SGI_COMPILER_VERSION/100) +# define COMPILER_VERSION_MINOR DEC(_SGI_COMPILER_VERSION/10 % 10) +# define COMPILER_VERSION_PATCH DEC(_SGI_COMPILER_VERSION % 10) +# else + /* _COMPILER_VERSION = VRP */ +# define COMPILER_VERSION_MAJOR DEC(_COMPILER_VERSION/100) +# define COMPILER_VERSION_MINOR DEC(_COMPILER_VERSION/10 % 10) +# define COMPILER_VERSION_PATCH DEC(_COMPILER_VERSION % 10) +# endif + +/* This compiler is either not known or is too old to define an + identification macro. Try to identify the platform and guess that + it is the native compiler. */ +#elif defined(__sgi) +# define COMPILER_ID "MIPSpro" + +#elif defined(__hpux) || defined(__hpua) +# define COMPILER_ID "HP" + +#else /* unknown compiler */ +# define COMPILER_ID "" + +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_compiler = "INFO" ":" "compiler[" COMPILER_ID "]"; + +/* Identify known platforms by name. */ +#if defined(__linux) || defined(__linux__) || defined(linux) +# define PLATFORM_ID "Linux" + +#elif defined(__CYGWIN__) +# define PLATFORM_ID "Cygwin" + +#elif defined(__MINGW32__) +# define PLATFORM_ID "MinGW" + +#elif defined(__APPLE__) +# define PLATFORM_ID "Darwin" + +#elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32) +# define PLATFORM_ID "Windows" + +#elif defined(__FreeBSD__) || defined(__FreeBSD) +# define PLATFORM_ID "FreeBSD" + +#elif defined(__NetBSD__) || defined(__NetBSD) +# define PLATFORM_ID "NetBSD" + +#elif defined(__OpenBSD__) || defined(__OPENBSD) +# define PLATFORM_ID "OpenBSD" + +#elif defined(__sun) || defined(sun) +# define PLATFORM_ID "SunOS" + +#elif defined(_AIX) || defined(__AIX) || defined(__AIX__) || defined(__aix) || defined(__aix__) +# define PLATFORM_ID "AIX" + +#elif defined(__sgi) || defined(__sgi__) || defined(_SGI) +# define PLATFORM_ID "IRIX" + +#elif defined(__hpux) || defined(__hpux__) +# define PLATFORM_ID "HP-UX" + +#elif defined(__HAIKU__) +# define PLATFORM_ID "Haiku" + +#elif defined(__BeOS) || defined(__BEOS__) || defined(_BEOS) +# define PLATFORM_ID "BeOS" + +#elif defined(__QNX__) || defined(__QNXNTO__) +# define PLATFORM_ID "QNX" + +#elif defined(__tru64) || defined(_tru64) || defined(__TRU64__) +# define PLATFORM_ID "Tru64" + +#elif defined(__riscos) || defined(__riscos__) +# define PLATFORM_ID "RISCos" + +#elif defined(__sinix) || defined(__sinix__) || defined(__SINIX__) +# define PLATFORM_ID "SINIX" + +#elif defined(__UNIX_SV__) +# define PLATFORM_ID "UNIX_SV" + +#elif defined(__bsdos__) +# define PLATFORM_ID "BSDOS" + +#elif defined(_MPRAS) || defined(MPRAS) +# define PLATFORM_ID "MP-RAS" + +#elif defined(__osf) || defined(__osf__) +# define PLATFORM_ID "OSF1" + +#elif defined(_SCO_SV) || defined(SCO_SV) || defined(sco_sv) +# define PLATFORM_ID "SCO_SV" + +#elif defined(__ultrix) || defined(__ultrix__) || defined(_ULTRIX) +# define PLATFORM_ID "ULTRIX" + +#elif defined(__XENIX__) || defined(_XENIX) || defined(XENIX) +# define PLATFORM_ID "Xenix" + +#else /* unknown platform */ +# define PLATFORM_ID "" + +#endif + +/* For windows compilers MSVC and Intel we can determine + the architecture of the compiler being used. This is because + the compilers do not have flags that can change the architecture, + but rather depend on which compiler is being used +*/ +#if defined(_WIN32) && defined(_MSC_VER) +# if defined(_M_IA64) +# define ARCHITECTURE_ID "IA64" + +# elif defined(_M_X64) || defined(_M_AMD64) +# define ARCHITECTURE_ID "x64" + +# elif defined(_M_IX86) +# define ARCHITECTURE_ID "X86" + +# elif defined(_M_ARM) +# define ARCHITECTURE_ID "ARM" + +# elif defined(_M_MIPS) +# define ARCHITECTURE_ID "MIPS" + +# elif defined(_M_SH) +# define ARCHITECTURE_ID "SHx" + +# else /* unknown architecture */ +# define ARCHITECTURE_ID "" +# endif + +#else +# define ARCHITECTURE_ID "" +#endif + +/* Convert integer to decimal digit literals. */ +#define DEC(n) \ + ('0' + (((n) / 10000000)%10)), \ + ('0' + (((n) / 1000000)%10)), \ + ('0' + (((n) / 100000)%10)), \ + ('0' + (((n) / 10000)%10)), \ + ('0' + (((n) / 1000)%10)), \ + ('0' + (((n) / 100)%10)), \ + ('0' + (((n) / 10)%10)), \ + ('0' + ((n) % 10)) + +/* Convert integer to hex digit literals. */ +#define HEX(n) \ + ('0' + ((n)>>28 & 0xF)), \ + ('0' + ((n)>>24 & 0xF)), \ + ('0' + ((n)>>20 & 0xF)), \ + ('0' + ((n)>>16 & 0xF)), \ + ('0' + ((n)>>12 & 0xF)), \ + ('0' + ((n)>>8 & 0xF)), \ + ('0' + ((n)>>4 & 0xF)), \ + ('0' + ((n) & 0xF)) + +/* Construct a string literal encoding the version number components. */ +#ifdef COMPILER_VERSION_MAJOR +char const info_version[] = { + 'I', 'N', 'F', 'O', ':', + 'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','[', + COMPILER_VERSION_MAJOR, +# ifdef COMPILER_VERSION_MINOR + '.', COMPILER_VERSION_MINOR, +# ifdef COMPILER_VERSION_PATCH + '.', COMPILER_VERSION_PATCH, +# ifdef COMPILER_VERSION_TWEAK + '.', COMPILER_VERSION_TWEAK, +# endif +# endif +# endif + ']','\0'}; +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_platform = "INFO" ":" "platform[" PLATFORM_ID "]"; +char const* info_arch = "INFO" ":" "arch[" ARCHITECTURE_ID "]"; + + + +/*--------------------------------------------------------------------------*/ + +#ifdef ID_VOID_MAIN +void main() {} +#else +int main(int argc, char* argv[]) +{ + int require = 0; + require += info_compiler[argc]; + require += info_platform[argc]; + require += info_arch[argc]; +#ifdef COMPILER_VERSION_MAJOR + require += info_version[argc]; +#endif + (void)argv; + return require; +} +#endif diff --git a/vSLAM/ch9 project/0.1/build/CMakeFiles/2.8.12.2/CompilerIdC/a.out b/vSLAM/ch9 project/0.1/build/CMakeFiles/2.8.12.2/CompilerIdC/a.out new file mode 100755 index 00000000..49a5ca2e Binary files /dev/null and b/vSLAM/ch9 project/0.1/build/CMakeFiles/2.8.12.2/CompilerIdC/a.out differ diff --git a/vSLAM/ch9 project/0.1/build/CMakeFiles/2.8.12.2/CompilerIdCXX/CMakeCXXCompilerId.cpp b/vSLAM/ch9 project/0.1/build/CMakeFiles/2.8.12.2/CompilerIdCXX/CMakeCXXCompilerId.cpp new file mode 100644 index 00000000..e8220b26 --- /dev/null +++ b/vSLAM/ch9 project/0.1/build/CMakeFiles/2.8.12.2/CompilerIdCXX/CMakeCXXCompilerId.cpp @@ -0,0 +1,377 @@ +/* This source file must have a .cpp extension so that all C++ compilers + recognize the extension without flags. Borland does not know .cxx for + example. */ +#ifndef __cplusplus +# error "A C compiler has been selected for C++." +#endif + +/* Version number components: V=Version, R=Revision, P=Patch + Version date components: YYYY=Year, MM=Month, DD=Day */ + +#if defined(__COMO__) +# define COMPILER_ID "Comeau" + /* __COMO_VERSION__ = VRR */ +# define COMPILER_VERSION_MAJOR DEC(__COMO_VERSION__ / 100) +# define COMPILER_VERSION_MINOR DEC(__COMO_VERSION__ % 100) + +#elif defined(__INTEL_COMPILER) || defined(__ICC) +# define COMPILER_ID "Intel" + /* __INTEL_COMPILER = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER/100) +# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER % 10) +# if defined(__INTEL_COMPILER_BUILD_DATE) + /* __INTEL_COMPILER_BUILD_DATE = YYYYMMDD */ +# define COMPILER_VERSION_TWEAK DEC(__INTEL_COMPILER_BUILD_DATE) +# endif + +#elif defined(__PATHCC__) +# define COMPILER_ID "PathScale" +# define COMPILER_VERSION_MAJOR DEC(__PATHCC__) +# define COMPILER_VERSION_MINOR DEC(__PATHCC_MINOR__) +# if defined(__PATHCC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__PATHCC_PATCHLEVEL__) +# endif + +#elif defined(__clang__) +# define COMPILER_ID "Clang" +# define COMPILER_VERSION_MAJOR DEC(__clang_major__) +# define COMPILER_VERSION_MINOR DEC(__clang_minor__) +# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__) + +#elif defined(__BORLANDC__) && defined(__CODEGEARC_VERSION__) +# define COMPILER_ID "Embarcadero" +# define COMPILER_VERSION_MAJOR HEX(__CODEGEARC_VERSION__>>24 & 0x00FF) +# define COMPILER_VERSION_MINOR HEX(__CODEGEARC_VERSION__>>16 & 0x00FF) +# define COMPILER_VERSION_PATCH HEX(__CODEGEARC_VERSION__ & 0xFFFF) + +#elif defined(__BORLANDC__) +# define COMPILER_ID "Borland" + /* __BORLANDC__ = 0xVRR */ +# define COMPILER_VERSION_MAJOR HEX(__BORLANDC__>>8) +# define COMPILER_VERSION_MINOR HEX(__BORLANDC__ & 0xFF) + +#elif defined(__WATCOMC__) +# define COMPILER_ID "Watcom" + /* __WATCOMC__ = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(__WATCOMC__ / 100) +# define COMPILER_VERSION_MINOR DEC(__WATCOMC__ % 100) + +#elif defined(__SUNPRO_CC) +# define COMPILER_ID "SunPro" +# if __SUNPRO_CC >= 0x5100 + /* __SUNPRO_CC = 0xVRRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_CC>>12) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_CC>>4 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_CC & 0xF) +# else + /* __SUNPRO_CC = 0xVRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_CC>>8) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_CC>>4 & 0xF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_CC & 0xF) +# endif + +#elif defined(__HP_aCC) +# define COMPILER_ID "HP" + /* __HP_aCC = VVRRPP */ +# define COMPILER_VERSION_MAJOR DEC(__HP_aCC/10000) +# define COMPILER_VERSION_MINOR DEC(__HP_aCC/100 % 100) +# define COMPILER_VERSION_PATCH DEC(__HP_aCC % 100) + +#elif defined(__DECCXX) +# define COMPILER_ID "Compaq" + /* __DECCXX_VER = VVRRTPPPP */ +# define COMPILER_VERSION_MAJOR DEC(__DECCXX_VER/10000000) +# define COMPILER_VERSION_MINOR DEC(__DECCXX_VER/100000 % 100) +# define COMPILER_VERSION_PATCH DEC(__DECCXX_VER % 10000) + +#elif defined(__IBMCPP__) +# if defined(__COMPILER_VER__) +# define COMPILER_ID "zOS" +# else +# if __IBMCPP__ >= 800 +# define COMPILER_ID "XL" +# else +# define COMPILER_ID "VisualAge" +# endif + /* __IBMCPP__ = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__IBMCPP__/100) +# define COMPILER_VERSION_MINOR DEC(__IBMCPP__/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__IBMCPP__ % 10) +# endif + +#elif defined(__PGI) +# define COMPILER_ID "PGI" +# define COMPILER_VERSION_MAJOR DEC(__PGIC__) +# define COMPILER_VERSION_MINOR DEC(__PGIC_MINOR__) +# if defined(__PGIC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__PGIC_PATCHLEVEL__) +# endif + +#elif defined(_CRAYC) +# define COMPILER_ID "Cray" +# define COMPILER_VERSION_MAJOR DEC(_RELEASE) +# define COMPILER_VERSION_MINOR DEC(_RELEASE_MINOR) + +#elif defined(__TI_COMPILER_VERSION__) +# define COMPILER_ID "TI" + /* __TI_COMPILER_VERSION__ = VVVRRRPPP */ +# define COMPILER_VERSION_MAJOR DEC(__TI_COMPILER_VERSION__/1000000) +# define COMPILER_VERSION_MINOR DEC(__TI_COMPILER_VERSION__/1000 % 1000) +# define COMPILER_VERSION_PATCH DEC(__TI_COMPILER_VERSION__ % 1000) + +#elif defined(__SCO_VERSION__) +# define COMPILER_ID "SCO" + +#elif defined(__GNUC__) +# define COMPILER_ID "GNU" +# define COMPILER_VERSION_MAJOR DEC(__GNUC__) +# define COMPILER_VERSION_MINOR DEC(__GNUC_MINOR__) +# if defined(__GNUC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__) +# endif + +#elif defined(_MSC_VER) +# define COMPILER_ID "MSVC" + /* _MSC_VER = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(_MSC_VER / 100) +# define COMPILER_VERSION_MINOR DEC(_MSC_VER % 100) +# if defined(_MSC_FULL_VER) +# if _MSC_VER >= 1400 + /* _MSC_FULL_VER = VVRRPPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 100000) +# else + /* _MSC_FULL_VER = VVRRPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 10000) +# endif +# endif +# if defined(_MSC_BUILD) +# define COMPILER_VERSION_TWEAK DEC(_MSC_BUILD) +# endif + +/* Analog VisualDSP++ >= 4.5.6 */ +#elif defined(__VISUALDSPVERSION__) +# define COMPILER_ID "ADSP" + /* __VISUALDSPVERSION__ = 0xVVRRPP00 */ +# define COMPILER_VERSION_MAJOR HEX(__VISUALDSPVERSION__>>24) +# define COMPILER_VERSION_MINOR HEX(__VISUALDSPVERSION__>>16 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__VISUALDSPVERSION__>>8 & 0xFF) + +/* Analog VisualDSP++ < 4.5.6 */ +#elif defined(__ADSPBLACKFIN__) || defined(__ADSPTS__) || defined(__ADSP21000__) +# define COMPILER_ID "ADSP" + +/* IAR Systems compiler for embedded systems. + http://www.iar.com */ +#elif defined(__IAR_SYSTEMS_ICC__ ) || defined(__IAR_SYSTEMS_ICC) +# define COMPILER_ID "IAR" + +#elif defined(_SGI_COMPILER_VERSION) || defined(_COMPILER_VERSION) +# define COMPILER_ID "MIPSpro" +# if defined(_SGI_COMPILER_VERSION) + /* _SGI_COMPILER_VERSION = VRP */ +# define COMPILER_VERSION_MAJOR DEC(_SGI_COMPILER_VERSION/100) +# define COMPILER_VERSION_MINOR DEC(_SGI_COMPILER_VERSION/10 % 10) +# define COMPILER_VERSION_PATCH DEC(_SGI_COMPILER_VERSION % 10) +# else + /* _COMPILER_VERSION = VRP */ +# define COMPILER_VERSION_MAJOR DEC(_COMPILER_VERSION/100) +# define COMPILER_VERSION_MINOR DEC(_COMPILER_VERSION/10 % 10) +# define COMPILER_VERSION_PATCH DEC(_COMPILER_VERSION % 10) +# endif + +/* This compiler is either not known or is too old to define an + identification macro. Try to identify the platform and guess that + it is the native compiler. */ +#elif defined(__sgi) +# define COMPILER_ID "MIPSpro" + +#elif defined(__hpux) || defined(__hpua) +# define COMPILER_ID "HP" + +#else /* unknown compiler */ +# define COMPILER_ID "" + +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_compiler = "INFO" ":" "compiler[" COMPILER_ID "]"; + +/* Identify known platforms by name. */ +#if defined(__linux) || defined(__linux__) || defined(linux) +# define PLATFORM_ID "Linux" + +#elif defined(__CYGWIN__) +# define PLATFORM_ID "Cygwin" + +#elif defined(__MINGW32__) +# define PLATFORM_ID "MinGW" + +#elif defined(__APPLE__) +# define PLATFORM_ID "Darwin" + +#elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32) +# define PLATFORM_ID "Windows" + +#elif defined(__FreeBSD__) || defined(__FreeBSD) +# define PLATFORM_ID "FreeBSD" + +#elif defined(__NetBSD__) || defined(__NetBSD) +# define PLATFORM_ID "NetBSD" + +#elif defined(__OpenBSD__) || defined(__OPENBSD) +# define PLATFORM_ID "OpenBSD" + +#elif defined(__sun) || defined(sun) +# define PLATFORM_ID "SunOS" + +#elif defined(_AIX) || defined(__AIX) || defined(__AIX__) || defined(__aix) || defined(__aix__) +# define PLATFORM_ID "AIX" + +#elif defined(__sgi) || defined(__sgi__) || defined(_SGI) +# define PLATFORM_ID "IRIX" + +#elif defined(__hpux) || defined(__hpux__) +# define PLATFORM_ID "HP-UX" + +#elif defined(__HAIKU__) +# define PLATFORM_ID "Haiku" + +#elif defined(__BeOS) || defined(__BEOS__) || defined(_BEOS) +# define PLATFORM_ID "BeOS" + +#elif defined(__QNX__) || defined(__QNXNTO__) +# define PLATFORM_ID "QNX" + +#elif defined(__tru64) || defined(_tru64) || defined(__TRU64__) +# define PLATFORM_ID "Tru64" + +#elif defined(__riscos) || defined(__riscos__) +# define PLATFORM_ID "RISCos" + +#elif defined(__sinix) || defined(__sinix__) || defined(__SINIX__) +# define PLATFORM_ID "SINIX" + +#elif defined(__UNIX_SV__) +# define PLATFORM_ID "UNIX_SV" + +#elif defined(__bsdos__) +# define PLATFORM_ID "BSDOS" + +#elif defined(_MPRAS) || defined(MPRAS) +# define PLATFORM_ID "MP-RAS" + +#elif defined(__osf) || defined(__osf__) +# define PLATFORM_ID "OSF1" + +#elif defined(_SCO_SV) || defined(SCO_SV) || defined(sco_sv) +# define PLATFORM_ID "SCO_SV" + +#elif defined(__ultrix) || defined(__ultrix__) || defined(_ULTRIX) +# define PLATFORM_ID "ULTRIX" + +#elif defined(__XENIX__) || defined(_XENIX) || defined(XENIX) +# define PLATFORM_ID "Xenix" + +#else /* unknown platform */ +# define PLATFORM_ID "" + +#endif + +/* For windows compilers MSVC and Intel we can determine + the architecture of the compiler being used. This is because + the compilers do not have flags that can change the architecture, + but rather depend on which compiler is being used +*/ +#if defined(_WIN32) && defined(_MSC_VER) +# if defined(_M_IA64) +# define ARCHITECTURE_ID "IA64" + +# elif defined(_M_X64) || defined(_M_AMD64) +# define ARCHITECTURE_ID "x64" + +# elif defined(_M_IX86) +# define ARCHITECTURE_ID "X86" + +# elif defined(_M_ARM) +# define ARCHITECTURE_ID "ARM" + +# elif defined(_M_MIPS) +# define ARCHITECTURE_ID "MIPS" + +# elif defined(_M_SH) +# define ARCHITECTURE_ID "SHx" + +# else /* unknown architecture */ +# define ARCHITECTURE_ID "" +# endif + +#else +# define ARCHITECTURE_ID "" +#endif + +/* Convert integer to decimal digit literals. */ +#define DEC(n) \ + ('0' + (((n) / 10000000)%10)), \ + ('0' + (((n) / 1000000)%10)), \ + ('0' + (((n) / 100000)%10)), \ + ('0' + (((n) / 10000)%10)), \ + ('0' + (((n) / 1000)%10)), \ + ('0' + (((n) / 100)%10)), \ + ('0' + (((n) / 10)%10)), \ + ('0' + ((n) % 10)) + +/* Convert integer to hex digit literals. */ +#define HEX(n) \ + ('0' + ((n)>>28 & 0xF)), \ + ('0' + ((n)>>24 & 0xF)), \ + ('0' + ((n)>>20 & 0xF)), \ + ('0' + ((n)>>16 & 0xF)), \ + ('0' + ((n)>>12 & 0xF)), \ + ('0' + ((n)>>8 & 0xF)), \ + ('0' + ((n)>>4 & 0xF)), \ + ('0' + ((n) & 0xF)) + +/* Construct a string literal encoding the version number components. */ +#ifdef COMPILER_VERSION_MAJOR +char const info_version[] = { + 'I', 'N', 'F', 'O', ':', + 'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','[', + COMPILER_VERSION_MAJOR, +# ifdef COMPILER_VERSION_MINOR + '.', COMPILER_VERSION_MINOR, +# ifdef COMPILER_VERSION_PATCH + '.', COMPILER_VERSION_PATCH, +# ifdef COMPILER_VERSION_TWEAK + '.', COMPILER_VERSION_TWEAK, +# endif +# endif +# endif + ']','\0'}; +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_platform = "INFO" ":" "platform[" PLATFORM_ID "]"; +char const* info_arch = "INFO" ":" "arch[" ARCHITECTURE_ID "]"; + + + +/*--------------------------------------------------------------------------*/ + +int main(int argc, char* argv[]) +{ + int require = 0; + require += info_compiler[argc]; + require += info_platform[argc]; +#ifdef COMPILER_VERSION_MAJOR + require += info_version[argc]; +#endif + (void)argv; + return require; +} diff --git a/vSLAM/ch9 project/0.1/build/CMakeFiles/2.8.12.2/CompilerIdCXX/a.out b/vSLAM/ch9 project/0.1/build/CMakeFiles/2.8.12.2/CompilerIdCXX/a.out new file mode 100755 index 00000000..96c16077 Binary files /dev/null and b/vSLAM/ch9 project/0.1/build/CMakeFiles/2.8.12.2/CompilerIdCXX/a.out differ diff --git a/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeDirectoryInformation.cmake b/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeDirectoryInformation.cmake new file mode 100644 index 00000000..e7e829c5 --- /dev/null +++ b/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeDirectoryInformation.cmake @@ -0,0 +1,16 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Relative path conversion top directories. +SET(CMAKE_RELATIVE_PATH_TOP_SOURCE "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1") +SET(CMAKE_RELATIVE_PATH_TOP_BINARY "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build") + +# Force unix paths in dependencies. +SET(CMAKE_FORCE_UNIX_PATHS 1) + + +# The C and CXX include file regular expressions for this directory. +SET(CMAKE_C_INCLUDE_REGEX_SCAN "^.*$") +SET(CMAKE_C_INCLUDE_REGEX_COMPLAIN "^$") +SET(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN}) +SET(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN}) diff --git a/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeOutput.log b/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeOutput.log new file mode 100644 index 00000000..6c2df7fc --- /dev/null +++ b/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeOutput.log @@ -0,0 +1,263 @@ +The system is: Linux - 4.4.0-94-generic - x86_64 +Compiling the C compiler identification source file "CMakeCCompilerId.c" succeeded. +Compiler: /usr/bin/cc +Build flags: +Id flags: + +The output was: +0 + + +Compilation of the C compiler identification source "CMakeCCompilerId.c" produced "a.out" + +The C compiler identification is GNU, found in "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles/2.8.12.2/CompilerIdC/a.out" + +Compiling the CXX compiler identification source file "CMakeCXXCompilerId.cpp" succeeded. +Compiler: /usr/bin/c++ +Build flags: +Id flags: + +The output was: +0 + + +Compilation of the CXX compiler identification source "CMakeCXXCompilerId.cpp" produced "a.out" + +The CXX compiler identification is GNU, found in "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles/2.8.12.2/CompilerIdCXX/a.out" + +Determining if the C compiler works passed with the following output: +Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeTmp + +Run Build Command:/usr/bin/make "cmTryCompileExec892401028/fast" +/usr/bin/make -f CMakeFiles/cmTryCompileExec892401028.dir/build.make CMakeFiles/cmTryCompileExec892401028.dir/build +make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeTmp' +/usr/bin/cmake -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeTmp/CMakeFiles" 1 +Building C object CMakeFiles/cmTryCompileExec892401028.dir/testCCompiler.c.o +/usr/bin/cc -o CMakeFiles/cmTryCompileExec892401028.dir/testCCompiler.c.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeTmp/testCCompiler.c" +Linking C executable cmTryCompileExec892401028 +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec892401028.dir/link.txt --verbose=1 +/usr/bin/cc CMakeFiles/cmTryCompileExec892401028.dir/testCCompiler.c.o -o cmTryCompileExec892401028 -rdynamic +make[1]: Leaving directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeTmp' + + +Detecting C compiler ABI info compiled with the following output: +Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeTmp + +Run Build Command:/usr/bin/make "cmTryCompileExec1379540920/fast" +/usr/bin/make -f CMakeFiles/cmTryCompileExec1379540920.dir/build.make CMakeFiles/cmTryCompileExec1379540920.dir/build +make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeTmp' +/usr/bin/cmake -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeTmp/CMakeFiles" 1 +Building C object CMakeFiles/cmTryCompileExec1379540920.dir/CMakeCCompilerABI.c.o +/usr/bin/cc -o CMakeFiles/cmTryCompileExec1379540920.dir/CMakeCCompilerABI.c.o -c /usr/share/cmake-2.8/Modules/CMakeCCompilerABI.c +Linking C executable cmTryCompileExec1379540920 +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec1379540920.dir/link.txt --verbose=1 +/usr/bin/cc -v CMakeFiles/cmTryCompileExec1379540920.dir/CMakeCCompilerABI.c.o -o cmTryCompileExec1379540920 -rdynamic +Using built-in specs. +COLLECT_GCC=/usr/bin/cc +COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/4.8/lto-wrapper +Target: x86_64-linux-gnu +Configured with: ../src/configure -v --with-pkgversion='Ubuntu 4.8.4-2ubuntu1~14.04.3' --with-bugurl=file:///usr/share/doc/gcc-4.8/README.Bugs --enable-languages=c,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-4.8 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --with-gxx-include-dir=/usr/include/c++/4.8 --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --enable-gnu-unique-object --disable-libmudflap --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-4.8-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu +Thread model: posix +gcc version 4.8.4 (Ubuntu 4.8.4-2ubuntu1~14.04.3) +COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/ +LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../:/lib/:/usr/lib/ +COLLECT_GCC_OPTIONS='-v' '-o' 'cmTryCompileExec1379540920' '-rdynamic' '-mtune=generic' '-march=x86-64' + /usr/lib/gcc/x86_64-linux-gnu/4.8/collect2 --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTryCompileExec1379540920 /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/4.8 -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../.. CMakeFiles/cmTryCompileExec1379540920.dir/CMakeCCompilerABI.c.o -lgcc --as-needed -lgcc_s --no-as-needed -lc -lgcc --as-needed -lgcc_s --no-as-needed /usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o +make[1]: Leaving directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeTmp' + + +Parsed C implicit link information from above output: + link line regex: [^( *|.*[/\])(ld|([^/\]+-)?ld|collect2)[^/\]*( |$)] + ignore line: [Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeTmp] + ignore line: [] + ignore line: [Run Build Command:/usr/bin/make "cmTryCompileExec1379540920/fast"] + ignore line: [/usr/bin/make -f CMakeFiles/cmTryCompileExec1379540920.dir/build.make CMakeFiles/cmTryCompileExec1379540920.dir/build] + ignore line: [make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeTmp'] + ignore line: [/usr/bin/cmake -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeTmp/CMakeFiles" 1] + ignore line: [Building C object CMakeFiles/cmTryCompileExec1379540920.dir/CMakeCCompilerABI.c.o] + ignore line: [/usr/bin/cc -o CMakeFiles/cmTryCompileExec1379540920.dir/CMakeCCompilerABI.c.o -c /usr/share/cmake-2.8/Modules/CMakeCCompilerABI.c] + ignore line: [Linking C executable cmTryCompileExec1379540920] + ignore line: [/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec1379540920.dir/link.txt --verbose=1] + ignore line: [/usr/bin/cc -v CMakeFiles/cmTryCompileExec1379540920.dir/CMakeCCompilerABI.c.o -o cmTryCompileExec1379540920 -rdynamic ] + ignore line: [Using built-in specs.] + ignore line: [COLLECT_GCC=/usr/bin/cc] + ignore line: [COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/4.8/lto-wrapper] + ignore line: [Target: x86_64-linux-gnu] + ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 4.8.4-2ubuntu1~14.04.3' --with-bugurl=file:///usr/share/doc/gcc-4.8/README.Bugs --enable-languages=c,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-4.8 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --with-gxx-include-dir=/usr/include/c++/4.8 --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --enable-gnu-unique-object --disable-libmudflap --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-4.8-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu] + ignore line: [Thread model: posix] + ignore line: [gcc version 4.8.4 (Ubuntu 4.8.4-2ubuntu1~14.04.3) ] + ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/] + ignore line: [LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../:/lib/:/usr/lib/] + ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'cmTryCompileExec1379540920' '-rdynamic' '-mtune=generic' '-march=x86-64'] + link line: [ /usr/lib/gcc/x86_64-linux-gnu/4.8/collect2 --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTryCompileExec1379540920 /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/4.8 -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../.. CMakeFiles/cmTryCompileExec1379540920.dir/CMakeCCompilerABI.c.o -lgcc --as-needed -lgcc_s --no-as-needed -lc -lgcc --as-needed -lgcc_s --no-as-needed /usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o] + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/collect2] ==> ignore + arg [--sysroot=/] ==> ignore + arg [--build-id] ==> ignore + arg [--eh-frame-hdr] ==> ignore + arg [-m] ==> ignore + arg [elf_x86_64] ==> ignore + arg [--hash-style=gnu] ==> ignore + arg [--as-needed] ==> ignore + arg [-export-dynamic] ==> ignore + arg [-dynamic-linker] ==> ignore + arg [/lib64/ld-linux-x86-64.so.2] ==> ignore + arg [-zrelro] ==> ignore + arg [-o] ==> ignore + arg [cmTryCompileExec1379540920] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o] ==> ignore + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] + arg [-L/lib/x86_64-linux-gnu] ==> dir [/lib/x86_64-linux-gnu] + arg [-L/lib/../lib] ==> dir [/lib/../lib] + arg [-L/usr/lib/x86_64-linux-gnu] ==> dir [/usr/lib/x86_64-linux-gnu] + arg [-L/usr/lib/../lib] ==> dir [/usr/lib/../lib] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] + arg [CMakeFiles/cmTryCompileExec1379540920.dir/CMakeCCompilerABI.c.o] ==> ignore + arg [-lgcc] ==> lib [gcc] + arg [--as-needed] ==> ignore + arg [-lgcc_s] ==> lib [gcc_s] + arg [--no-as-needed] ==> ignore + arg [-lc] ==> lib [c] + arg [-lgcc] ==> lib [gcc] + arg [--as-needed] ==> ignore + arg [-lgcc_s] ==> lib [gcc_s] + arg [--no-as-needed] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o] ==> ignore + remove lib [gcc] + remove lib [gcc_s] + remove lib [gcc] + remove lib [gcc_s] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8] ==> [/usr/lib/gcc/x86_64-linux-gnu/4.8] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] ==> [/usr/lib] + collapse library dir [/lib/x86_64-linux-gnu] ==> [/lib/x86_64-linux-gnu] + collapse library dir [/lib/../lib] ==> [/lib] + collapse library dir [/usr/lib/x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/../lib] ==> [/usr/lib] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] ==> [/usr/lib] + implicit libs: [c] + implicit dirs: [/usr/lib/gcc/x86_64-linux-gnu/4.8;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib] + implicit fwks: [] + + +Determining if the CXX compiler works passed with the following output: +Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeTmp + +Run Build Command:/usr/bin/make "cmTryCompileExec1334350884/fast" +/usr/bin/make -f CMakeFiles/cmTryCompileExec1334350884.dir/build.make CMakeFiles/cmTryCompileExec1334350884.dir/build +make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeTmp' +/usr/bin/cmake -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeTmp/CMakeFiles" 1 +Building CXX object CMakeFiles/cmTryCompileExec1334350884.dir/testCXXCompiler.cxx.o +/usr/bin/c++ -o CMakeFiles/cmTryCompileExec1334350884.dir/testCXXCompiler.cxx.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeTmp/testCXXCompiler.cxx" +Linking CXX executable cmTryCompileExec1334350884 +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec1334350884.dir/link.txt --verbose=1 +/usr/bin/c++ CMakeFiles/cmTryCompileExec1334350884.dir/testCXXCompiler.cxx.o -o cmTryCompileExec1334350884 -rdynamic +make[1]: Leaving directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeTmp' + + +Detecting CXX compiler ABI info compiled with the following output: +Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeTmp + +Run Build Command:/usr/bin/make "cmTryCompileExec1206608208/fast" +/usr/bin/make -f CMakeFiles/cmTryCompileExec1206608208.dir/build.make CMakeFiles/cmTryCompileExec1206608208.dir/build +make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeTmp' +/usr/bin/cmake -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeTmp/CMakeFiles" 1 +Building CXX object CMakeFiles/cmTryCompileExec1206608208.dir/CMakeCXXCompilerABI.cpp.o +/usr/bin/c++ -o CMakeFiles/cmTryCompileExec1206608208.dir/CMakeCXXCompilerABI.cpp.o -c /usr/share/cmake-2.8/Modules/CMakeCXXCompilerABI.cpp +Linking CXX executable cmTryCompileExec1206608208 +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec1206608208.dir/link.txt --verbose=1 +/usr/bin/c++ -v CMakeFiles/cmTryCompileExec1206608208.dir/CMakeCXXCompilerABI.cpp.o -o cmTryCompileExec1206608208 -rdynamic +Using built-in specs. +COLLECT_GCC=/usr/bin/c++ +COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/4.8/lto-wrapper +Target: x86_64-linux-gnu +Configured with: ../src/configure -v --with-pkgversion='Ubuntu 4.8.4-2ubuntu1~14.04.3' --with-bugurl=file:///usr/share/doc/gcc-4.8/README.Bugs --enable-languages=c,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-4.8 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --with-gxx-include-dir=/usr/include/c++/4.8 --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --enable-gnu-unique-object --disable-libmudflap --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-4.8-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu +Thread model: posix +gcc version 4.8.4 (Ubuntu 4.8.4-2ubuntu1~14.04.3) +COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/ +LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../:/lib/:/usr/lib/ +COLLECT_GCC_OPTIONS='-v' '-o' 'cmTryCompileExec1206608208' '-rdynamic' '-shared-libgcc' '-mtune=generic' '-march=x86-64' + /usr/lib/gcc/x86_64-linux-gnu/4.8/collect2 --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTryCompileExec1206608208 /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/4.8 -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../.. CMakeFiles/cmTryCompileExec1206608208.dir/CMakeCXXCompilerABI.cpp.o -lstdc++ -lm -lgcc_s -lgcc -lc -lgcc_s -lgcc /usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o +make[1]: Leaving directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeTmp' + + +Parsed CXX implicit link information from above output: + link line regex: [^( *|.*[/\])(ld|([^/\]+-)?ld|collect2)[^/\]*( |$)] + ignore line: [Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeTmp] + ignore line: [] + ignore line: [Run Build Command:/usr/bin/make "cmTryCompileExec1206608208/fast"] + ignore line: [/usr/bin/make -f CMakeFiles/cmTryCompileExec1206608208.dir/build.make CMakeFiles/cmTryCompileExec1206608208.dir/build] + ignore line: [make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeTmp'] + ignore line: [/usr/bin/cmake -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles/CMakeTmp/CMakeFiles" 1] + ignore line: [Building CXX object CMakeFiles/cmTryCompileExec1206608208.dir/CMakeCXXCompilerABI.cpp.o] + ignore line: [/usr/bin/c++ -o CMakeFiles/cmTryCompileExec1206608208.dir/CMakeCXXCompilerABI.cpp.o -c /usr/share/cmake-2.8/Modules/CMakeCXXCompilerABI.cpp] + ignore line: [Linking CXX executable cmTryCompileExec1206608208] + ignore line: [/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec1206608208.dir/link.txt --verbose=1] + ignore line: [/usr/bin/c++ -v CMakeFiles/cmTryCompileExec1206608208.dir/CMakeCXXCompilerABI.cpp.o -o cmTryCompileExec1206608208 -rdynamic ] + ignore line: [Using built-in specs.] + ignore line: [COLLECT_GCC=/usr/bin/c++] + ignore line: [COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/4.8/lto-wrapper] + ignore line: [Target: x86_64-linux-gnu] + ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 4.8.4-2ubuntu1~14.04.3' --with-bugurl=file:///usr/share/doc/gcc-4.8/README.Bugs --enable-languages=c,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-4.8 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --with-gxx-include-dir=/usr/include/c++/4.8 --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --enable-gnu-unique-object --disable-libmudflap --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-4.8-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu] + ignore line: [Thread model: posix] + ignore line: [gcc version 4.8.4 (Ubuntu 4.8.4-2ubuntu1~14.04.3) ] + ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/] + ignore line: [LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../:/lib/:/usr/lib/] + ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'cmTryCompileExec1206608208' '-rdynamic' '-shared-libgcc' '-mtune=generic' '-march=x86-64'] + link line: [ /usr/lib/gcc/x86_64-linux-gnu/4.8/collect2 --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTryCompileExec1206608208 /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/4.8 -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../.. CMakeFiles/cmTryCompileExec1206608208.dir/CMakeCXXCompilerABI.cpp.o -lstdc++ -lm -lgcc_s -lgcc -lc -lgcc_s -lgcc /usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o] + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/collect2] ==> ignore + arg [--sysroot=/] ==> ignore + arg [--build-id] ==> ignore + arg [--eh-frame-hdr] ==> ignore + arg [-m] ==> ignore + arg [elf_x86_64] ==> ignore + arg [--hash-style=gnu] ==> ignore + arg [--as-needed] ==> ignore + arg [-export-dynamic] ==> ignore + arg [-dynamic-linker] ==> ignore + arg [/lib64/ld-linux-x86-64.so.2] ==> ignore + arg [-zrelro] ==> ignore + arg [-o] ==> ignore + arg [cmTryCompileExec1206608208] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o] ==> ignore + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] + arg [-L/lib/x86_64-linux-gnu] ==> dir [/lib/x86_64-linux-gnu] + arg [-L/lib/../lib] ==> dir [/lib/../lib] + arg [-L/usr/lib/x86_64-linux-gnu] ==> dir [/usr/lib/x86_64-linux-gnu] + arg [-L/usr/lib/../lib] ==> dir [/usr/lib/../lib] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] + arg [CMakeFiles/cmTryCompileExec1206608208.dir/CMakeCXXCompilerABI.cpp.o] ==> ignore + arg [-lstdc++] ==> lib [stdc++] + arg [-lm] ==> lib [m] + arg [-lgcc_s] ==> lib [gcc_s] + arg [-lgcc] ==> lib [gcc] + arg [-lc] ==> lib [c] + arg [-lgcc_s] ==> lib [gcc_s] + arg [-lgcc] ==> lib [gcc] + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o] ==> ignore + remove lib [gcc_s] + remove lib [gcc] + remove lib [gcc_s] + remove lib [gcc] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8] ==> [/usr/lib/gcc/x86_64-linux-gnu/4.8] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] ==> [/usr/lib] + collapse library dir [/lib/x86_64-linux-gnu] ==> [/lib/x86_64-linux-gnu] + collapse library dir [/lib/../lib] ==> [/lib] + collapse library dir [/usr/lib/x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/../lib] ==> [/usr/lib] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] ==> [/usr/lib] + implicit libs: [stdc++;m;c] + implicit dirs: [/usr/lib/gcc/x86_64-linux-gnu/4.8;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib] + implicit fwks: [] + + diff --git a/vSLAM/ch9 project/0.1/build/CMakeFiles/Makefile.cmake b/vSLAM/ch9 project/0.1/build/CMakeFiles/Makefile.cmake new file mode 100644 index 00000000..688695fa --- /dev/null +++ b/vSLAM/ch9 project/0.1/build/CMakeFiles/Makefile.cmake @@ -0,0 +1,53 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# The generator used is: +SET(CMAKE_DEPENDS_GENERATOR "Unix Makefiles") + +# The top level Makefile was generated from the following files: +SET(CMAKE_MAKEFILE_DEPENDS + "CMakeCache.txt" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build/SophusConfig.cmake" + "../CMakeLists.txt" + "CMakeFiles/2.8.12.2/CMakeCCompiler.cmake" + "CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake" + "CMakeFiles/2.8.12.2/CMakeSystem.cmake" + "../cmake_modules/FindG2O.cmake" + "../src/CMakeLists.txt" + "../test/CMakeLists.txt" + "/usr/local/share/OpenCV/OpenCVConfig-version.cmake" + "/usr/local/share/OpenCV/OpenCVConfig.cmake" + "/usr/local/share/OpenCV/OpenCVModules-release.cmake" + "/usr/local/share/OpenCV/OpenCVModules.cmake" + "/usr/share/cmake-2.8/Modules/CMakeCInformation.cmake" + "/usr/share/cmake-2.8/Modules/CMakeCXXInformation.cmake" + "/usr/share/cmake-2.8/Modules/CMakeCommonLanguageInclude.cmake" + "/usr/share/cmake-2.8/Modules/CMakeGenericSystem.cmake" + "/usr/share/cmake-2.8/Modules/CMakeSystemSpecificInformation.cmake" + "/usr/share/cmake-2.8/Modules/Compiler/GNU-C.cmake" + "/usr/share/cmake-2.8/Modules/Compiler/GNU-CXX.cmake" + "/usr/share/cmake-2.8/Modules/Compiler/GNU.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux-GNU-C.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux-GNU-CXX.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux-GNU.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux.cmake" + "/usr/share/cmake-2.8/Modules/Platform/UnixPaths.cmake" + ) + +# The corresponding makefile is: +SET(CMAKE_MAKEFILE_OUTPUTS + "Makefile" + "CMakeFiles/cmake.check_cache" + ) + +# Byproducts of CMake generate step: +SET(CMAKE_MAKEFILE_PRODUCTS + "CMakeFiles/CMakeDirectoryInformation.cmake" + "src/CMakeFiles/CMakeDirectoryInformation.cmake" + "test/CMakeFiles/CMakeDirectoryInformation.cmake" + ) + +# Dependency information for all targets: +SET(CMAKE_DEPEND_INFO_FILES + "src/CMakeFiles/myslam.dir/DependInfo.cmake" + ) diff --git a/vSLAM/ch9 project/0.1/build/CMakeFiles/Makefile2 b/vSLAM/ch9 project/0.1/build/CMakeFiles/Makefile2 new file mode 100644 index 00000000..45f7aa23 --- /dev/null +++ b/vSLAM/ch9 project/0.1/build/CMakeFiles/Makefile2 @@ -0,0 +1,129 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Default target executed when no arguments are given to make. +default_target: all +.PHONY : default_target + +# The main recursive all target +all: +.PHONY : all + +# The main recursive preinstall target +preinstall: +.PHONY : preinstall + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1" + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" + +#============================================================================= +# Directory level rules for directory src + +# Convenience name for "all" pass in the directory. +src/all: src/CMakeFiles/myslam.dir/all +.PHONY : src/all + +# Convenience name for "clean" pass in the directory. +src/clean: src/CMakeFiles/myslam.dir/clean +.PHONY : src/clean + +# Convenience name for "preinstall" pass in the directory. +src/preinstall: +.PHONY : src/preinstall + +#============================================================================= +# Target rules for target src/CMakeFiles/myslam.dir + +# All Build rule for target. +src/CMakeFiles/myslam.dir/all: + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/depend + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/build + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles" 1 2 3 4 5 + @echo "Built target myslam" +.PHONY : src/CMakeFiles/myslam.dir/all + +# Include target in all. +all: src/CMakeFiles/myslam.dir/all +.PHONY : all + +# Build rule for subdir invocation for target. +src/CMakeFiles/myslam.dir/rule: cmake_check_build_system + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles" 5 + $(MAKE) -f CMakeFiles/Makefile2 src/CMakeFiles/myslam.dir/all + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles" 0 +.PHONY : src/CMakeFiles/myslam.dir/rule + +# Convenience name for target. +myslam: src/CMakeFiles/myslam.dir/rule +.PHONY : myslam + +# clean rule for target. +src/CMakeFiles/myslam.dir/clean: + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/clean +.PHONY : src/CMakeFiles/myslam.dir/clean + +# clean rule for target. +clean: src/CMakeFiles/myslam.dir/clean +.PHONY : clean + +#============================================================================= +# Directory level rules for directory test + +# Convenience name for "all" pass in the directory. +test/all: +.PHONY : test/all + +# Convenience name for "clean" pass in the directory. +test/clean: +.PHONY : test/clean + +# Convenience name for "preinstall" pass in the directory. +test/preinstall: +.PHONY : test/preinstall + +#============================================================================= +# Special targets to cleanup operation of make. + +# Special rule to run CMake to check the build system integrity. +# No rule that depends on this can have commands that come from listfiles +# because they might be regenerated. +cmake_check_build_system: + $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0 +.PHONY : cmake_check_build_system + diff --git a/vSLAM/ch9 project/0.1/build/CMakeFiles/TargetDirectories.txt b/vSLAM/ch9 project/0.1/build/CMakeFiles/TargetDirectories.txt new file mode 100644 index 00000000..3daf8859 --- /dev/null +++ b/vSLAM/ch9 project/0.1/build/CMakeFiles/TargetDirectories.txt @@ -0,0 +1 @@ +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir diff --git a/vSLAM/ch9 project/0.1/build/CMakeFiles/cmake.check_cache b/vSLAM/ch9 project/0.1/build/CMakeFiles/cmake.check_cache new file mode 100644 index 00000000..3dccd731 --- /dev/null +++ b/vSLAM/ch9 project/0.1/build/CMakeFiles/cmake.check_cache @@ -0,0 +1 @@ +# This file is generated by cmake for dependency checking of the CMakeCache.txt file diff --git a/vSLAM/ch9 project/0.1/build/CMakeFiles/progress.marks b/vSLAM/ch9 project/0.1/build/CMakeFiles/progress.marks new file mode 100644 index 00000000..7ed6ff82 --- /dev/null +++ b/vSLAM/ch9 project/0.1/build/CMakeFiles/progress.marks @@ -0,0 +1 @@ +5 diff --git a/vSLAM/ch9 project/0.1/build/Makefile b/vSLAM/ch9 project/0.1/build/Makefile new file mode 100644 index 00000000..acaa6c2b --- /dev/null +++ b/vSLAM/ch9 project/0.1/build/Makefile @@ -0,0 +1,136 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Default target executed when no arguments are given to make. +default_target: all +.PHONY : default_target + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1" + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" + +#============================================================================= +# Targets provided globally by CMake. + +# Special rule for the target edit_cache +edit_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running interactive CMake command-line interface..." + /usr/bin/cmake -i . +.PHONY : edit_cache + +# Special rule for the target edit_cache +edit_cache/fast: edit_cache +.PHONY : edit_cache/fast + +# Special rule for the target rebuild_cache +rebuild_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake to regenerate build system..." + /usr/bin/cmake -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) +.PHONY : rebuild_cache + +# Special rule for the target rebuild_cache +rebuild_cache/fast: rebuild_cache +.PHONY : rebuild_cache/fast + +# The main all target +all: cmake_check_build_system + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles/progress.marks" + $(MAKE) -f CMakeFiles/Makefile2 all + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles" 0 +.PHONY : all + +# The main clean target +clean: + $(MAKE) -f CMakeFiles/Makefile2 clean +.PHONY : clean + +# The main clean target +clean/fast: clean +.PHONY : clean/fast + +# Prepare targets for installation. +preinstall: all + $(MAKE) -f CMakeFiles/Makefile2 preinstall +.PHONY : preinstall + +# Prepare targets for installation. +preinstall/fast: + $(MAKE) -f CMakeFiles/Makefile2 preinstall +.PHONY : preinstall/fast + +# clear depends +depend: + $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 1 +.PHONY : depend + +#============================================================================= +# Target rules for targets named myslam + +# Build rule for target. +myslam: cmake_check_build_system + $(MAKE) -f CMakeFiles/Makefile2 myslam +.PHONY : myslam + +# fast build rule for target. +myslam/fast: + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/build +.PHONY : myslam/fast + +# Help Target +help: + @echo "The following are some of the valid targets for this Makefile:" + @echo "... all (the default if no target is provided)" + @echo "... clean" + @echo "... depend" + @echo "... edit_cache" + @echo "... rebuild_cache" + @echo "... myslam" +.PHONY : help + + + +#============================================================================= +# Special targets to cleanup operation of make. + +# Special rule to run CMake to check the build system integrity. +# No rule that depends on this can have commands that come from listfiles +# because they might be regenerated. +cmake_check_build_system: + $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0 +.PHONY : cmake_check_build_system + diff --git a/vSLAM/ch9 project/0.1/build/cmake_install.cmake b/vSLAM/ch9 project/0.1/build/cmake_install.cmake new file mode 100644 index 00000000..c781a7db --- /dev/null +++ b/vSLAM/ch9 project/0.1/build/cmake_install.cmake @@ -0,0 +1,51 @@ +# Install script for directory: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1 + +# Set the install prefix +IF(NOT DEFINED CMAKE_INSTALL_PREFIX) + SET(CMAKE_INSTALL_PREFIX "/usr/local") +ENDIF(NOT DEFINED CMAKE_INSTALL_PREFIX) +STRING(REGEX REPLACE "/$" "" CMAKE_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}") + +# Set the install configuration name. +IF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + IF(BUILD_TYPE) + STRING(REGEX REPLACE "^[^A-Za-z0-9_]+" "" + CMAKE_INSTALL_CONFIG_NAME "${BUILD_TYPE}") + ELSE(BUILD_TYPE) + SET(CMAKE_INSTALL_CONFIG_NAME "Release") + ENDIF(BUILD_TYPE) + MESSAGE(STATUS "Install configuration: \"${CMAKE_INSTALL_CONFIG_NAME}\"") +ENDIF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + +# Set the component getting installed. +IF(NOT CMAKE_INSTALL_COMPONENT) + IF(COMPONENT) + MESSAGE(STATUS "Install component: \"${COMPONENT}\"") + SET(CMAKE_INSTALL_COMPONENT "${COMPONENT}") + ELSE(COMPONENT) + SET(CMAKE_INSTALL_COMPONENT) + ENDIF(COMPONENT) +ENDIF(NOT CMAKE_INSTALL_COMPONENT) + +# Install shared libraries without execute permission? +IF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + SET(CMAKE_INSTALL_SO_NO_EXE "1") +ENDIF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + +IF(NOT CMAKE_INSTALL_LOCAL_ONLY) + # Include the install script for each subdirectory. + INCLUDE("/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/src/cmake_install.cmake") + INCLUDE("/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/test/cmake_install.cmake") + +ENDIF(NOT CMAKE_INSTALL_LOCAL_ONLY) + +IF(CMAKE_INSTALL_COMPONENT) + SET(CMAKE_INSTALL_MANIFEST "install_manifest_${CMAKE_INSTALL_COMPONENT}.txt") +ELSE(CMAKE_INSTALL_COMPONENT) + SET(CMAKE_INSTALL_MANIFEST "install_manifest.txt") +ENDIF(CMAKE_INSTALL_COMPONENT) + +FILE(WRITE "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/${CMAKE_INSTALL_MANIFEST}" "") +FOREACH(file ${CMAKE_INSTALL_MANIFEST_FILES}) + FILE(APPEND "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/${CMAKE_INSTALL_MANIFEST}" "${file}\n") +ENDFOREACH(file) diff --git a/vSLAM/ch9 project/0.1/build/src/CMakeFiles/CMakeDirectoryInformation.cmake b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/CMakeDirectoryInformation.cmake new file mode 100644 index 00000000..e7e829c5 --- /dev/null +++ b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/CMakeDirectoryInformation.cmake @@ -0,0 +1,16 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Relative path conversion top directories. +SET(CMAKE_RELATIVE_PATH_TOP_SOURCE "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1") +SET(CMAKE_RELATIVE_PATH_TOP_BINARY "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build") + +# Force unix paths in dependencies. +SET(CMAKE_FORCE_UNIX_PATHS 1) + + +# The C and CXX include file regular expressions for this directory. +SET(CMAKE_C_INCLUDE_REGEX_SCAN "^.*$") +SET(CMAKE_C_INCLUDE_REGEX_COMPLAIN "^$") +SET(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN}) +SET(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN}) diff --git a/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/CXX.includecache b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/CXX.includecache new file mode 100644 index 00000000..3258f5c2 --- /dev/null +++ b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/CXX.includecache @@ -0,0 +1,1536 @@ +#IncludeRegexLine: ^[ ]*#[ ]*(include|import)[ ]*[<"]([^">]+)([">]) + +#IncludeRegexScan: ^.*$ + +#IncludeRegexComplain: ^$ + +#IncludeRegexTransform: + +../include/myslam/camera.h +myslam/common_include.h +../include/myslam/myslam/common_include.h + +../include/myslam/common_include.h +Eigen/Core +- +Eigen/Geometry +- +sophus/se3.h +- +opencv2/core/core.hpp +- +vector +- +list +- +memory +- +string +- +iostream +- +set +- +unordered_map +- +map +- + +../include/myslam/frame.h +myslam/common_include.h +../include/myslam/myslam/common_include.h +myslam/camera.h +../include/myslam/myslam/camera.h + +../include/myslam/map.h +myslam/common_include.h +../include/myslam/myslam/common_include.h +myslam/frame.h +../include/myslam/myslam/frame.h +myslam/mappoint.h +../include/myslam/myslam/mappoint.h + +../include/myslam/mappoint.h + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +so3.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +Eigen/Core +- +Eigen/StdVector +- +Eigen/Geometry +- + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/camera.cpp +myslam/camera.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/myslam/camera.h + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/frame.cpp +myslam/frame.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/myslam/frame.h + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/map.cpp +myslam/map.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/myslam/map.h + +/usr/include/eigen3/Eigen/Cholesky +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/Cholesky/LLT.h +/usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/Cholesky/LDLT.h +/usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/Cholesky/LLT_MKL.h +/usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Core/util/Macros.h +/usr/include/eigen3/Eigen/src/Core/util/Macros.h +complex +- +src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +malloc.h +- +immintrin.h +- +emmintrin.h +- +xmmintrin.h +- +pmmintrin.h +- +tmmintrin.h +- +smmintrin.h +- +nmmintrin.h +- +altivec.h +- +arm_neon.h +- +omp.h +- +cerrno +- +cstddef +- +cstdlib +- +cmath +- +cassert +- +functional +- +iosfwd +- +cstring +- +string +- +limits +- +climits +- +algorithm +- +iostream +- +intrin.h +- +new +- +src/Core/util/Constants.h +/usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/Core/util/ForwardDeclarations.h +/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/Core/util/Meta.h +/usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/Core/util/StaticAssert.h +/usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/Core/util/XprHelper.h +/usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/Core/util/Memory.h +/usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/Core/NumTraits.h +/usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/Core/MathFunctions.h +/usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/Core/GenericPacketMath.h +/usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/Core/arch/SSE/PacketMath.h +/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/Core/arch/SSE/MathFunctions.h +/usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/Core/arch/SSE/Complex.h +/usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/Core/arch/AltiVec/PacketMath.h +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/Core/arch/AltiVec/Complex.h +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/Core/arch/NEON/PacketMath.h +/usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/Core/arch/NEON/Complex.h +/usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/Core/arch/Default/Settings.h +/usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/Core/Functors.h +/usr/include/eigen3/Eigen/src/Core/Functors.h +src/Core/DenseCoeffsBase.h +/usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/Core/DenseBase.h +/usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/Core/MatrixBase.h +/usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/Core/EigenBase.h +/usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/Core/Assign.h +/usr/include/eigen3/Eigen/src/Core/Assign.h +src/Core/util/BlasUtil.h +/usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/Core/DenseStorage.h +/usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/Core/NestByValue.h +/usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/Core/ForceAlignedAccess.h +/usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/Core/ReturnByValue.h +/usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/Core/NoAlias.h +/usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/Core/PlainObjectBase.h +/usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/Core/Matrix.h +/usr/include/eigen3/Eigen/src/Core/Matrix.h +src/Core/Array.h +/usr/include/eigen3/Eigen/src/Core/Array.h +src/Core/CwiseBinaryOp.h +/usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/Core/CwiseUnaryOp.h +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/Core/CwiseNullaryOp.h +/usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/Core/CwiseUnaryView.h +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/Core/SelfCwiseBinaryOp.h +/usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/Core/Dot.h +/usr/include/eigen3/Eigen/src/Core/Dot.h +src/Core/StableNorm.h +/usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/Core/MapBase.h +/usr/include/eigen3/Eigen/src/Core/MapBase.h +src/Core/Stride.h +/usr/include/eigen3/Eigen/src/Core/Stride.h +src/Core/Map.h +/usr/include/eigen3/Eigen/src/Core/Map.h +src/Core/Block.h +/usr/include/eigen3/Eigen/src/Core/Block.h +src/Core/VectorBlock.h +/usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/Core/Ref.h +/usr/include/eigen3/Eigen/src/Core/Ref.h +src/Core/Transpose.h +/usr/include/eigen3/Eigen/src/Core/Transpose.h +src/Core/DiagonalMatrix.h +/usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/Core/Diagonal.h +/usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/Core/DiagonalProduct.h +/usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/Core/PermutationMatrix.h +/usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/Core/Transpositions.h +/usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/Core/Redux.h +/usr/include/eigen3/Eigen/src/Core/Redux.h +src/Core/Visitor.h +/usr/include/eigen3/Eigen/src/Core/Visitor.h +src/Core/Fuzzy.h +/usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/Core/IO.h +/usr/include/eigen3/Eigen/src/Core/IO.h +src/Core/Swap.h +/usr/include/eigen3/Eigen/src/Core/Swap.h +src/Core/CommaInitializer.h +/usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/Core/Flagged.h +/usr/include/eigen3/Eigen/src/Core/Flagged.h +src/Core/ProductBase.h +/usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/Core/GeneralProduct.h +/usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/Core/TriangularMatrix.h +/usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/Core/SelfAdjointView.h +/usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/Core/products/GeneralBlockPanelKernel.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/Core/products/Parallelizer.h +/usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/Core/products/CoeffBasedProduct.h +/usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/Core/products/GeneralMatrixVector.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/Core/products/GeneralMatrixMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/Core/SolveTriangular.h +/usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/Core/products/GeneralMatrixMatrixTriangular.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/Core/products/SelfadjointMatrixVector.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/Core/products/SelfadjointMatrixMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/Core/products/SelfadjointProduct.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/Core/products/SelfadjointRank2Update.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/Core/products/TriangularMatrixVector.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/Core/products/TriangularMatrixMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/Core/products/TriangularSolverMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/Core/products/TriangularSolverVector.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/Core/BandMatrix.h +/usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/Core/CoreIterators.h +/usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/Core/BooleanRedux.h +/usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/Core/Select.h +/usr/include/eigen3/Eigen/src/Core/Select.h +src/Core/VectorwiseOp.h +/usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/Core/Random.h +/usr/include/eigen3/Eigen/src/Core/Random.h +src/Core/Replicate.h +/usr/include/eigen3/Eigen/src/Core/Replicate.h +src/Core/Reverse.h +/usr/include/eigen3/Eigen/src/Core/Reverse.h +src/Core/ArrayBase.h +/usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/Core/ArrayWrapper.h +/usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/Core/products/GeneralMatrixMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/Core/products/GeneralMatrixVector_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/Core/products/SelfadjointMatrixMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/Core/products/SelfadjointMatrixVector_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/Core/products/TriangularMatrixMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/Core/products/TriangularMatrixVector_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/Core/products/TriangularSolverMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/Core/Assign_MKL.h +/usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/Core/GlobalFunctions.h +/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +Eigen2Support +/usr/include/eigen3/Eigen/Eigen2Support + +/usr/include/eigen3/Eigen/Eigen2Support +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Eigen2Support/Macros.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/Eigen2Support/Memory.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/Eigen2Support/Meta.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/Eigen2Support/Lazy.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/Eigen2Support/Cwise.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/Eigen2Support/CwiseOperators.h +/usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/Eigen2Support/TriangularSolver.h +/usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/Eigen2Support/Block.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/Eigen2Support/VectorBlock.h +/usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/Eigen2Support/Minor.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/Eigen2Support/MathFunctions.h +/usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +iostream +- + +/usr/include/eigen3/Eigen/Eigenvalues +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +Cholesky +/usr/include/eigen3/Eigen/Cholesky +Jacobi +/usr/include/eigen3/Eigen/Jacobi +Householder +/usr/include/eigen3/Eigen/Householder +LU +/usr/include/eigen3/Eigen/LU +Geometry +/usr/include/eigen3/Eigen/Geometry +src/Eigenvalues/Tridiagonalization.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/Eigenvalues/RealSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/Eigenvalues/EigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/Eigenvalues/SelfAdjointEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/Eigenvalues/HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/Eigenvalues/ComplexSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/Eigenvalues/ComplexEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/Eigenvalues/RealQZ.h +/usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/Eigenvalues/GeneralizedEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/Eigenvalues/MatrixBaseEigenvalues.h +/usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/Eigenvalues/RealSchur_MKL.h +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/Eigenvalues/ComplexSchur_MKL.h +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Geometry +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +SVD +/usr/include/eigen3/Eigen/SVD +LU +/usr/include/eigen3/Eigen/LU +limits +- +src/Geometry/OrthoMethods.h +/usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/Geometry/EulerAngles.h +/usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/Geometry/Homogeneous.h +/usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/Geometry/RotationBase.h +/usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/Geometry/Rotation2D.h +/usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/Geometry/Quaternion.h +/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/Geometry/AngleAxis.h +/usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/Geometry/Transform.h +/usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/Geometry/Translation.h +/usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/Geometry/Scaling.h +/usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/Geometry/Hyperplane.h +/usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/Geometry/ParametrizedLine.h +/usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/Geometry/AlignedBox.h +/usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/Geometry/Umeyama.h +/usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/Geometry/arch/Geometry_SSE.h +/usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/Eigen2Support/Geometry/All.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Householder +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Householder/Householder.h +/usr/include/eigen3/Eigen/src/Householder/Householder.h +src/Householder/HouseholderSequence.h +/usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/Householder/BlockHouseholder.h +/usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Jacobi +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Jacobi/Jacobi.h +/usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/LU +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/misc/Kernel.h +/usr/include/eigen3/Eigen/src/misc/Kernel.h +src/misc/Image.h +/usr/include/eigen3/Eigen/src/misc/Image.h +src/LU/FullPivLU.h +/usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/LU/PartialPivLU.h +/usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/LU/PartialPivLU_MKL.h +/usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/LU/Determinant.h +/usr/include/eigen3/Eigen/src/LU/Determinant.h +src/LU/Inverse.h +/usr/include/eigen3/Eigen/src/LU/Inverse.h +src/LU/arch/Inverse_SSE.h +/usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/Eigen2Support/LU.h +/usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/QR +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +Cholesky +/usr/include/eigen3/Eigen/Cholesky +Jacobi +/usr/include/eigen3/Eigen/Jacobi +Householder +/usr/include/eigen3/Eigen/Householder +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/QR/HouseholderQR.h +/usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/QR/FullPivHouseholderQR.h +/usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/QR/ColPivHouseholderQR.h +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/QR/HouseholderQR_MKL.h +/usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/QR/ColPivHouseholderQR_MKL.h +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/Eigen2Support/QR.h +/usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +Eigenvalues +/usr/include/eigen3/Eigen/Eigenvalues + +/usr/include/eigen3/Eigen/SVD +QR +/usr/include/eigen3/Eigen/QR +Householder +/usr/include/eigen3/Eigen/Householder +Jacobi +/usr/include/eigen3/Eigen/Jacobi +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/SVD/JacobiSVD.h +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/SVD/JacobiSVD_MKL.h +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/SVD/UpperBidiagonalization.h +/usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/Eigen2Support/SVD.h +/usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/StdVector +Core +/usr/include/eigen3/Eigen/Core +vector +- +src/StlSupport/StdVector.h +/usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + +/usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + +/usr/include/eigen3/Eigen/src/Cholesky/LLT.h + +/usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Cholesky/Eigen/src/Core/util/MKL_support.h +iostream +- + +/usr/include/eigen3/Eigen/src/Core/Array.h + +/usr/include/eigen3/Eigen/src/Core/ArrayBase.h +../plugins/CommonCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +../plugins/MatrixCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +../plugins/ArrayCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +../plugins/CommonCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +../plugins/MatrixCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +../plugins/ArrayCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + +/usr/include/eigen3/Eigen/src/Core/Assign.h + +/usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + +/usr/include/eigen3/Eigen/src/Core/BandMatrix.h + +/usr/include/eigen3/Eigen/src/Core/Block.h + +/usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + +/usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + +/usr/include/eigen3/Eigen/src/Core/CoreIterators.h + +/usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + +/usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + +/usr/include/eigen3/Eigen/src/Core/DenseBase.h +../plugins/BlockMethods.h +/usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + +/usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + +/usr/include/eigen3/Eigen/src/Core/DenseStorage.h + +/usr/include/eigen3/Eigen/src/Core/Diagonal.h + +/usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + +/usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + +/usr/include/eigen3/Eigen/src/Core/Dot.h + +/usr/include/eigen3/Eigen/src/Core/EigenBase.h + +/usr/include/eigen3/Eigen/src/Core/Flagged.h + +/usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + +/usr/include/eigen3/Eigen/src/Core/Functors.h + +/usr/include/eigen3/Eigen/src/Core/Fuzzy.h + +/usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + +/usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + +/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + +/usr/include/eigen3/Eigen/src/Core/IO.h + +/usr/include/eigen3/Eigen/src/Core/Map.h + +/usr/include/eigen3/Eigen/src/Core/MapBase.h + +/usr/include/eigen3/Eigen/src/Core/MathFunctions.h + +/usr/include/eigen3/Eigen/src/Core/Matrix.h + +/usr/include/eigen3/Eigen/src/Core/MatrixBase.h +../plugins/CommonCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +../plugins/CommonCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +../plugins/MatrixCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +../plugins/MatrixCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/Core/NestByValue.h + +/usr/include/eigen3/Eigen/src/Core/NoAlias.h + +/usr/include/eigen3/Eigen/src/Core/NumTraits.h + +/usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + +/usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + +/usr/include/eigen3/Eigen/src/Core/ProductBase.h + +/usr/include/eigen3/Eigen/src/Core/Random.h + +/usr/include/eigen3/Eigen/src/Core/Redux.h + +/usr/include/eigen3/Eigen/src/Core/Ref.h + +/usr/include/eigen3/Eigen/src/Core/Replicate.h + +/usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + +/usr/include/eigen3/Eigen/src/Core/Reverse.h + +/usr/include/eigen3/Eigen/src/Core/Select.h + +/usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + +/usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + +/usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + +/usr/include/eigen3/Eigen/src/Core/StableNorm.h + +/usr/include/eigen3/Eigen/src/Core/Stride.h + +/usr/include/eigen3/Eigen/src/Core/Swap.h + +/usr/include/eigen3/Eigen/src/Core/Transpose.h + +/usr/include/eigen3/Eigen/src/Core/Transpositions.h + +/usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + +/usr/include/eigen3/Eigen/src/Core/VectorBlock.h + +/usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + +/usr/include/eigen3/Eigen/src/Core/Visitor.h + +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + +/usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + +/usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + +/usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + +/usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + +/usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + +/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + +/usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + +/usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + +/usr/include/eigen3/Eigen/src/Core/util/Constants.h + +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + +/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + +/usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +mkl.h +- +mkl_lapacke.h +- + +/usr/include/eigen3/Eigen/src/Core/util/Macros.h +cstdlib +- +iostream +- + +/usr/include/eigen3/Eigen/src/Core/util/Memory.h +unistd.h +- + +/usr/include/eigen3/Eigen/src/Core/util/Meta.h + +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + +/usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +limits +- +RotationBase.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +Rotation2D.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +Quaternion.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +AngleAxis.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +Transform.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +Translation.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +Scaling.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +AlignedBox.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +Hyperplane.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +ParametrizedLine.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +RotationBase.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +Rotation2D.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +Quaternion.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +AngleAxis.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +Transform.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +Translation.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +Scaling.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +AlignedBox.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +Hyperplane.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +ParametrizedLine.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/././HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/././HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +./ComplexSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +./RealSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +./RealQZ.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +./Tridiagonalization.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +./Tridiagonalization.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + +/usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + +/usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + +/usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + +/usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + +/usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + +/usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + +/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + +/usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + +/usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + +/usr/include/eigen3/Eigen/src/Geometry/Scaling.h + +/usr/include/eigen3/Eigen/src/Geometry/Transform.h + +/usr/include/eigen3/Eigen/src/Geometry/Translation.h + +/usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + +/usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + +/usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + +/usr/include/eigen3/Eigen/src/Householder/Householder.h + +/usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + +/usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + +/usr/include/eigen3/Eigen/src/LU/Determinant.h + +/usr/include/eigen3/Eigen/src/LU/FullPivLU.h + +/usr/include/eigen3/Eigen/src/LU/Inverse.h + +/usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + +/usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/LU/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/QR/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + +/usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + +/usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/QR/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/SVD/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + +/usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +Eigen/src/StlSupport/details.h +/usr/include/eigen3/Eigen/src/StlSupport/Eigen/src/StlSupport/details.h + +/usr/include/eigen3/Eigen/src/StlSupport/details.h + +/usr/include/eigen3/Eigen/src/misc/Image.h + +/usr/include/eigen3/Eigen/src/misc/Kernel.h + +/usr/include/eigen3/Eigen/src/misc/Solve.h + +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + +/usr/local/include/opencv/cxcore.h +opencv2/core/core_c.h +/usr/local/include/opencv/opencv2/core/core_c.h + +/usr/local/include/opencv2/calib3d.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/opencv2/features2d.hpp +opencv2/core/affine.hpp +/usr/local/include/opencv2/opencv2/core/affine.hpp +opencv2/calib3d/calib3d_c.h +/usr/local/include/opencv2/opencv2/calib3d/calib3d_c.h + +/usr/local/include/opencv2/calib3d/calib3d_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/calib3d/opencv2/core/core_c.h + +/usr/local/include/opencv2/core.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/opencv2/core/cvdef.h +opencv2/core/version.hpp +/usr/local/include/opencv2/opencv2/core/version.hpp +opencv2/core/base.hpp +/usr/local/include/opencv2/opencv2/core/base.hpp +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/opencv2/core/cvstd.hpp +opencv2/core/traits.hpp +/usr/local/include/opencv2/opencv2/core/traits.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/opencv2/core/matx.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/opencv2/core/types.hpp +opencv2/core/mat.hpp +/usr/local/include/opencv2/opencv2/core/mat.hpp +opencv2/core/persistence.hpp +/usr/local/include/opencv2/opencv2/core/persistence.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/opencv2/opencv.hpp +opencv2/xfeatures2d.hpp +/usr/local/include/opencv2/opencv2/xfeatures2d.hpp +opencv2/core/operations.hpp +/usr/local/include/opencv2/opencv2/core/operations.hpp +opencv2/core/cvstd.inl.hpp +/usr/local/include/opencv2/opencv2/core/cvstd.inl.hpp +opencv2/core/utility.hpp +/usr/local/include/opencv2/opencv2/core/utility.hpp +opencv2/core/optim.hpp +/usr/local/include/opencv2/opencv2/core/optim.hpp + +/usr/local/include/opencv2/core/affine.hpp +opencv2/core.hpp +- + +/usr/local/include/opencv2/core/base.hpp +climits +- +algorithm +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/core/opencv2/core/cvstd.hpp +opencv2/core/neon_utils.hpp +/usr/local/include/opencv2/core/opencv2/core/neon_utils.hpp + +/usr/local/include/opencv2/core/bufferpool.hpp + +/usr/local/include/opencv2/core/core.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/core_c.h +opencv2/core/types_c.h +/usr/local/include/opencv2/core/opencv2/core/types_c.h +cxcore.h +/usr/local/include/opencv2/core/cxcore.h +cxcore.h +/usr/local/include/opencv2/core/cxcore.h +opencv2/core/utility.hpp +/usr/local/include/opencv2/core/opencv2/core/utility.hpp + +/usr/local/include/opencv2/core/cvdef.h +limits.h +- +opencv2/core/hal/interface.h +/usr/local/include/opencv2/core/opencv2/core/hal/interface.h +emmintrin.h +- +pmmintrin.h +- +tmmintrin.h +- +smmintrin.h +- +nmmintrin.h +- +nmmintrin.h +- +popcntintrin.h +- +immintrin.h +- +immintrin.h +- +Intrin.h +- +arm_neon.h +/usr/local/include/opencv2/core/arm_neon.h +arm_neon.h +- +intrin.h +- + +/usr/local/include/opencv2/core/cvstd.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +cstddef +- +cstring +- +cctype +- +string +- +algorithm +- +utility +- +cstdlib +- +cmath +- +opencv2/core/ptr.inl.hpp +/usr/local/include/opencv2/core/opencv2/core/ptr.inl.hpp + +/usr/local/include/opencv2/core/cvstd.inl.hpp +complex +- +ostream +- + +/usr/local/include/opencv2/core/fast_math.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +fastmath.h +- +cmath +- +math.h +- +tegra_round.hpp +/usr/local/include/opencv2/core/tegra_round.hpp + +/usr/local/include/opencv2/core/hal/interface.h +cstddef +- +stddef.h +- +cstdint +- +stdint.h +- + +/usr/local/include/opencv2/core/mat.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/core/opencv2/core/matx.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/core/opencv2/core/types.hpp +opencv2/core/bufferpool.hpp +/usr/local/include/opencv2/core/opencv2/core/bufferpool.hpp +opencv2/core/mat.inl.hpp +/usr/local/include/opencv2/core/opencv2/core/mat.inl.hpp + +/usr/local/include/opencv2/core/mat.inl.hpp + +/usr/local/include/opencv2/core/matx.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/base.hpp +/usr/local/include/opencv2/core/opencv2/core/base.hpp +opencv2/core/traits.hpp +/usr/local/include/opencv2/core/opencv2/core/traits.hpp +opencv2/core/saturate.hpp +/usr/local/include/opencv2/core/opencv2/core/saturate.hpp + +/usr/local/include/opencv2/core/neon_utils.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h + +/usr/local/include/opencv2/core/operations.hpp +cstdio +- + +/usr/local/include/opencv2/core/optim.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/persistence.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/core/opencv2/core/types.hpp +opencv2/core/mat.hpp +/usr/local/include/opencv2/core/opencv2/core/mat.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/core/opencv2/opencv.hpp +time.h +- + +/usr/local/include/opencv2/core/ptr.inl.hpp +algorithm +- + +/usr/local/include/opencv2/core/saturate.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/fast_math.hpp +/usr/local/include/opencv2/core/opencv2/core/fast_math.hpp + +/usr/local/include/opencv2/core/traits.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h + +/usr/local/include/opencv2/core/types.hpp +climits +- +cfloat +- +vector +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/core/opencv2/core/cvstd.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/core/opencv2/core/matx.hpp + +/usr/local/include/opencv2/core/types_c.h +ipl.h +- +ipl/ipl.h +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +assert.h +- +stdlib.h +- +string.h +- +float.h +- +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/utility.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp +opencv2/core/core_c.h +/usr/local/include/opencv2/core/opencv2/core/core_c.h + +/usr/local/include/opencv2/core/version.hpp + +/usr/local/include/opencv2/features2d.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/flann/miniflann.hpp +/usr/local/include/opencv2/opencv2/flann/miniflann.hpp + +/usr/local/include/opencv2/flann/config.h + +/usr/local/include/opencv2/flann/defines.h +config.h +/usr/local/include/opencv2/flann/config.h + +/usr/local/include/opencv2/flann/miniflann.hpp +opencv2/core.hpp +/usr/local/include/opencv2/flann/opencv2/core.hpp +opencv2/flann/defines.h +/usr/local/include/opencv2/flann/opencv2/flann/defines.h + +/usr/local/include/opencv2/highgui.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgcodecs.hpp +/usr/local/include/opencv2/opencv2/imgcodecs.hpp +opencv2/videoio.hpp +/usr/local/include/opencv2/opencv2/videoio.hpp +opencv2/highgui/highgui_c.h +/usr/local/include/opencv2/opencv2/highgui/highgui_c.h + +/usr/local/include/opencv2/highgui/highgui_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/highgui/opencv2/core/core_c.h +opencv2/imgproc/imgproc_c.h +/usr/local/include/opencv2/highgui/opencv2/imgproc/imgproc_c.h +opencv2/imgcodecs/imgcodecs_c.h +/usr/local/include/opencv2/highgui/opencv2/imgcodecs/imgcodecs_c.h +opencv2/videoio/videoio_c.h +/usr/local/include/opencv2/highgui/opencv2/videoio/videoio_c.h + +/usr/local/include/opencv2/imgcodecs.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/opencv.hpp +- + +/usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/imgcodecs/opencv2/core/core_c.h + +/usr/local/include/opencv2/imgproc.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/core.hpp +- +opencv2/imgproc.hpp +- +opencv2/imgcodecs.hpp +- +opencv2/highgui.hpp +- +iostream +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +math.h +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/opencv2/highgui.hpp +opencv2/imgproc/imgproc_c.h +/usr/local/include/opencv2/opencv2/imgproc/imgproc_c.h + +/usr/local/include/opencv2/imgproc/imgproc_c.h +opencv2/imgproc/types_c.h +/usr/local/include/opencv2/imgproc/opencv2/imgproc/types_c.h + +/usr/local/include/opencv2/imgproc/types_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/imgproc/opencv2/core/core_c.h + +/usr/local/include/opencv2/ml.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +float.h +- +map +- +iostream +- + +/usr/local/include/opencv2/objdetect.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/objdetect/detection_based_tracker.hpp +/usr/local/include/opencv2/opencv2/objdetect/detection_based_tracker.hpp +opencv2/objdetect/objdetect_c.h +/usr/local/include/opencv2/opencv2/objdetect/objdetect_c.h + +/usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +vector +- + +/usr/local/include/opencv2/objdetect/objdetect_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/objdetect/opencv2/core/core_c.h +deque +- +vector +- + +/usr/local/include/opencv2/opencv.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/photo.hpp +/usr/local/include/opencv2/opencv2/photo.hpp +opencv2/video.hpp +/usr/local/include/opencv2/opencv2/video.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/opencv2/features2d.hpp +opencv2/objdetect.hpp +/usr/local/include/opencv2/opencv2/objdetect.hpp +opencv2/calib3d.hpp +/usr/local/include/opencv2/opencv2/calib3d.hpp +opencv2/imgcodecs.hpp +/usr/local/include/opencv2/opencv2/imgcodecs.hpp +opencv2/videoio.hpp +/usr/local/include/opencv2/opencv2/videoio.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/opencv2/highgui.hpp +opencv2/ml.hpp +/usr/local/include/opencv2/opencv2/ml.hpp + +/usr/local/include/opencv2/photo.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/photo/photo_c.h +/usr/local/include/opencv2/opencv2/photo/photo_c.h + +/usr/local/include/opencv2/photo/photo_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/photo/opencv2/core/core_c.h + +/usr/local/include/opencv2/video.hpp +opencv2/video/tracking.hpp +/usr/local/include/opencv2/opencv2/video/tracking.hpp +opencv2/video/background_segm.hpp +/usr/local/include/opencv2/opencv2/video/background_segm.hpp +opencv2/video/tracking_c.h +/usr/local/include/opencv2/opencv2/video/tracking_c.h + +/usr/local/include/opencv2/video/background_segm.hpp +opencv2/core.hpp +/usr/local/include/opencv2/video/opencv2/core.hpp + +/usr/local/include/opencv2/video/tracking.hpp +opencv2/core.hpp +/usr/local/include/opencv2/video/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/video/opencv2/imgproc.hpp + +/usr/local/include/opencv2/video/tracking_c.h +opencv2/imgproc/types_c.h +/usr/local/include/opencv2/video/opencv2/imgproc/types_c.h + +/usr/local/include/opencv2/videoio.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/opencv2/opencv.hpp + +/usr/local/include/opencv2/videoio/videoio_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/videoio/opencv2/core/core_c.h + diff --git a/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/DependInfo.cmake b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/DependInfo.cmake new file mode 100644 index 00000000..be713bf6 --- /dev/null +++ b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/DependInfo.cmake @@ -0,0 +1,29 @@ +# The set of languages for which implicit dependencies are needed: +SET(CMAKE_DEPENDS_LANGUAGES + "CXX" + ) +# The set of files for implicit dependencies of each language: +SET(CMAKE_DEPENDS_CHECK_CXX + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/camera.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/camera.cpp.o" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/config.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/config.cpp.o" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/frame.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/frame.cpp.o" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/map.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/map.cpp.o" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/mappoint.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/mappoint.cpp.o" + ) +SET(CMAKE_CXX_COMPILER_ID "GNU") + +# Targets to which this target links. +SET(CMAKE_TARGET_LINKED_INFO_FILES + ) + +# The include file search paths: +SET(CMAKE_C_TARGET_INCLUDE_PATH + "/usr/include/eigen3" + "/usr/local/include/opencv" + "/usr/local/include" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus" + "../include" + ) +SET(CMAKE_CXX_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) +SET(CMAKE_Fortran_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) +SET(CMAKE_ASM_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) diff --git a/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/build.make b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/build.make new file mode 100644 index 00000000..f6ba4f8c --- /dev/null +++ b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/build.make @@ -0,0 +1,233 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1" + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" + +# Include any dependencies generated for this target. +include src/CMakeFiles/myslam.dir/depend.make + +# Include the progress variables for this target. +include src/CMakeFiles/myslam.dir/progress.make + +# Include the compile flags for this target's objects. +include src/CMakeFiles/myslam.dir/flags.make + +src/CMakeFiles/myslam.dir/frame.cpp.o: src/CMakeFiles/myslam.dir/flags.make +src/CMakeFiles/myslam.dir/frame.cpp.o: ../src/frame.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles" $(CMAKE_PROGRESS_1) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object src/CMakeFiles/myslam.dir/frame.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/myslam.dir/frame.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/frame.cpp" + +src/CMakeFiles/myslam.dir/frame.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/myslam.dir/frame.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/frame.cpp" > CMakeFiles/myslam.dir/frame.cpp.i + +src/CMakeFiles/myslam.dir/frame.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/myslam.dir/frame.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/frame.cpp" -o CMakeFiles/myslam.dir/frame.cpp.s + +src/CMakeFiles/myslam.dir/frame.cpp.o.requires: +.PHONY : src/CMakeFiles/myslam.dir/frame.cpp.o.requires + +src/CMakeFiles/myslam.dir/frame.cpp.o.provides: src/CMakeFiles/myslam.dir/frame.cpp.o.requires + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/frame.cpp.o.provides.build +.PHONY : src/CMakeFiles/myslam.dir/frame.cpp.o.provides + +src/CMakeFiles/myslam.dir/frame.cpp.o.provides.build: src/CMakeFiles/myslam.dir/frame.cpp.o + +src/CMakeFiles/myslam.dir/mappoint.cpp.o: src/CMakeFiles/myslam.dir/flags.make +src/CMakeFiles/myslam.dir/mappoint.cpp.o: ../src/mappoint.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles" $(CMAKE_PROGRESS_2) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object src/CMakeFiles/myslam.dir/mappoint.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/myslam.dir/mappoint.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/mappoint.cpp" + +src/CMakeFiles/myslam.dir/mappoint.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/myslam.dir/mappoint.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/mappoint.cpp" > CMakeFiles/myslam.dir/mappoint.cpp.i + +src/CMakeFiles/myslam.dir/mappoint.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/myslam.dir/mappoint.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/mappoint.cpp" -o CMakeFiles/myslam.dir/mappoint.cpp.s + +src/CMakeFiles/myslam.dir/mappoint.cpp.o.requires: +.PHONY : src/CMakeFiles/myslam.dir/mappoint.cpp.o.requires + +src/CMakeFiles/myslam.dir/mappoint.cpp.o.provides: src/CMakeFiles/myslam.dir/mappoint.cpp.o.requires + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/mappoint.cpp.o.provides.build +.PHONY : src/CMakeFiles/myslam.dir/mappoint.cpp.o.provides + +src/CMakeFiles/myslam.dir/mappoint.cpp.o.provides.build: src/CMakeFiles/myslam.dir/mappoint.cpp.o + +src/CMakeFiles/myslam.dir/map.cpp.o: src/CMakeFiles/myslam.dir/flags.make +src/CMakeFiles/myslam.dir/map.cpp.o: ../src/map.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles" $(CMAKE_PROGRESS_3) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object src/CMakeFiles/myslam.dir/map.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/myslam.dir/map.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/map.cpp" + +src/CMakeFiles/myslam.dir/map.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/myslam.dir/map.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/map.cpp" > CMakeFiles/myslam.dir/map.cpp.i + +src/CMakeFiles/myslam.dir/map.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/myslam.dir/map.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/map.cpp" -o CMakeFiles/myslam.dir/map.cpp.s + +src/CMakeFiles/myslam.dir/map.cpp.o.requires: +.PHONY : src/CMakeFiles/myslam.dir/map.cpp.o.requires + +src/CMakeFiles/myslam.dir/map.cpp.o.provides: src/CMakeFiles/myslam.dir/map.cpp.o.requires + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/map.cpp.o.provides.build +.PHONY : src/CMakeFiles/myslam.dir/map.cpp.o.provides + +src/CMakeFiles/myslam.dir/map.cpp.o.provides.build: src/CMakeFiles/myslam.dir/map.cpp.o + +src/CMakeFiles/myslam.dir/camera.cpp.o: src/CMakeFiles/myslam.dir/flags.make +src/CMakeFiles/myslam.dir/camera.cpp.o: ../src/camera.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles" $(CMAKE_PROGRESS_4) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object src/CMakeFiles/myslam.dir/camera.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/myslam.dir/camera.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/camera.cpp" + +src/CMakeFiles/myslam.dir/camera.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/myslam.dir/camera.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/camera.cpp" > CMakeFiles/myslam.dir/camera.cpp.i + +src/CMakeFiles/myslam.dir/camera.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/myslam.dir/camera.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/camera.cpp" -o CMakeFiles/myslam.dir/camera.cpp.s + +src/CMakeFiles/myslam.dir/camera.cpp.o.requires: +.PHONY : src/CMakeFiles/myslam.dir/camera.cpp.o.requires + +src/CMakeFiles/myslam.dir/camera.cpp.o.provides: src/CMakeFiles/myslam.dir/camera.cpp.o.requires + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/camera.cpp.o.provides.build +.PHONY : src/CMakeFiles/myslam.dir/camera.cpp.o.provides + +src/CMakeFiles/myslam.dir/camera.cpp.o.provides.build: src/CMakeFiles/myslam.dir/camera.cpp.o + +src/CMakeFiles/myslam.dir/config.cpp.o: src/CMakeFiles/myslam.dir/flags.make +src/CMakeFiles/myslam.dir/config.cpp.o: ../src/config.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles" $(CMAKE_PROGRESS_5) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object src/CMakeFiles/myslam.dir/config.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/myslam.dir/config.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/config.cpp" + +src/CMakeFiles/myslam.dir/config.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/myslam.dir/config.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/config.cpp" > CMakeFiles/myslam.dir/config.cpp.i + +src/CMakeFiles/myslam.dir/config.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/myslam.dir/config.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/config.cpp" -o CMakeFiles/myslam.dir/config.cpp.s + +src/CMakeFiles/myslam.dir/config.cpp.o.requires: +.PHONY : src/CMakeFiles/myslam.dir/config.cpp.o.requires + +src/CMakeFiles/myslam.dir/config.cpp.o.provides: src/CMakeFiles/myslam.dir/config.cpp.o.requires + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/config.cpp.o.provides.build +.PHONY : src/CMakeFiles/myslam.dir/config.cpp.o.provides + +src/CMakeFiles/myslam.dir/config.cpp.o.provides.build: src/CMakeFiles/myslam.dir/config.cpp.o + +# Object files for target myslam +myslam_OBJECTS = \ +"CMakeFiles/myslam.dir/frame.cpp.o" \ +"CMakeFiles/myslam.dir/mappoint.cpp.o" \ +"CMakeFiles/myslam.dir/map.cpp.o" \ +"CMakeFiles/myslam.dir/camera.cpp.o" \ +"CMakeFiles/myslam.dir/config.cpp.o" + +# External object files for target myslam +myslam_EXTERNAL_OBJECTS = + +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/frame.cpp.o +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/mappoint.cpp.o +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/map.cpp.o +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/camera.cpp.o +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/config.cpp.o +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/build.make +../lib/libmyslam.so: /usr/local/lib/libopencv_viz.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_videostab.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_videoio.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_video.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_superres.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_stitching.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_shape.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_photo.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_objdetect.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_ml.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_imgproc.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_imgcodecs.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_highgui.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_flann.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_features2d.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_core.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_calib3d.so.3.1.0 +../lib/libmyslam.so: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build/libSophus.so +../lib/libmyslam.so: /usr/local/lib/libopencv_features2d.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_ml.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_highgui.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_videoio.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_imgcodecs.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_flann.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_video.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_imgproc.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_core.so.3.1.0 +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/link.txt + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --red --bold "Linking CXX shared library ../../lib/libmyslam.so" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/src" && $(CMAKE_COMMAND) -E cmake_link_script CMakeFiles/myslam.dir/link.txt --verbose=$(VERBOSE) + +# Rule to build all files generated by this target. +src/CMakeFiles/myslam.dir/build: ../lib/libmyslam.so +.PHONY : src/CMakeFiles/myslam.dir/build + +src/CMakeFiles/myslam.dir/requires: src/CMakeFiles/myslam.dir/frame.cpp.o.requires +src/CMakeFiles/myslam.dir/requires: src/CMakeFiles/myslam.dir/mappoint.cpp.o.requires +src/CMakeFiles/myslam.dir/requires: src/CMakeFiles/myslam.dir/map.cpp.o.requires +src/CMakeFiles/myslam.dir/requires: src/CMakeFiles/myslam.dir/camera.cpp.o.requires +src/CMakeFiles/myslam.dir/requires: src/CMakeFiles/myslam.dir/config.cpp.o.requires +.PHONY : src/CMakeFiles/myslam.dir/requires + +src/CMakeFiles/myslam.dir/clean: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/src" && $(CMAKE_COMMAND) -P CMakeFiles/myslam.dir/cmake_clean.cmake +.PHONY : src/CMakeFiles/myslam.dir/clean + +src/CMakeFiles/myslam.dir/depend: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/src" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/DependInfo.cmake" --color=$(COLOR) +.PHONY : src/CMakeFiles/myslam.dir/depend + diff --git a/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/camera.cpp.o b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/camera.cpp.o new file mode 100644 index 00000000..4324efb8 Binary files /dev/null and b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/camera.cpp.o differ diff --git a/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/cmake_clean.cmake b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/cmake_clean.cmake new file mode 100644 index 00000000..ab8c38ab --- /dev/null +++ b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/cmake_clean.cmake @@ -0,0 +1,14 @@ +FILE(REMOVE_RECURSE + "CMakeFiles/myslam.dir/frame.cpp.o" + "CMakeFiles/myslam.dir/mappoint.cpp.o" + "CMakeFiles/myslam.dir/map.cpp.o" + "CMakeFiles/myslam.dir/camera.cpp.o" + "CMakeFiles/myslam.dir/config.cpp.o" + "../../lib/libmyslam.pdb" + "../../lib/libmyslam.so" +) + +# Per-language clean rules from dependency scanning. +FOREACH(lang CXX) + INCLUDE(CMakeFiles/myslam.dir/cmake_clean_${lang}.cmake OPTIONAL) +ENDFOREACH(lang) diff --git a/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/config.cpp.o b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/config.cpp.o new file mode 100644 index 00000000..efc49619 Binary files /dev/null and b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/config.cpp.o differ diff --git a/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/depend.internal b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/depend.internal new file mode 100644 index 00000000..74ef0962 --- /dev/null +++ b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/depend.internal @@ -0,0 +1,1317 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +src/CMakeFiles/myslam.dir/camera.cpp.o + ../include/myslam/camera.h + ../include/myslam/common_include.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/camera.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h +src/CMakeFiles/myslam.dir/config.cpp.o + ../include/myslam/common_include.h + ../include/myslam/config.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/config.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o + ../include/myslam/camera.h + ../include/myslam/common_include.h + ../include/myslam/frame.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/frame.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h +src/CMakeFiles/myslam.dir/map.cpp.o + ../include/myslam/camera.h + ../include/myslam/common_include.h + ../include/myslam/frame.h + ../include/myslam/map.h + ../include/myslam/mappoint.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/map.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o + ../include/myslam/common_include.h + ../include/myslam/mappoint.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src/mappoint.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h diff --git a/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/depend.make b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/depend.make new file mode 100644 index 00000000..8bd5f53b --- /dev/null +++ b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/depend.make @@ -0,0 +1,1317 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +src/CMakeFiles/myslam.dir/camera.cpp.o: ../include/myslam/camera.h +src/CMakeFiles/myslam.dir/camera.cpp.o: ../include/myslam/common_include.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +src/CMakeFiles/myslam.dir/camera.cpp.o: ../src/camera.cpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Cholesky +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Core +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Geometry +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Householder +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Jacobi +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/LU +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/QR +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/SVD +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/StdVector +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv/cxcore.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/calib3d.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/affine.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/base.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/core.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/core_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/cvdef.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/mat.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/matx.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/operations.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/optim.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/traits.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/types.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/types_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/utility.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/version.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/features2d.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/flann/config.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/flann/defines.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/highgui.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/imgproc.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/ml.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/objdetect.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/opencv.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/photo.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/video.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/videoio.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + +src/CMakeFiles/myslam.dir/config.cpp.o: ../include/myslam/common_include.h +src/CMakeFiles/myslam.dir/config.cpp.o: ../include/myslam/config.h +src/CMakeFiles/myslam.dir/config.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +src/CMakeFiles/myslam.dir/config.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +src/CMakeFiles/myslam.dir/config.cpp.o: ../src/config.cpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Cholesky +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Core +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Geometry +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Householder +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Jacobi +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/LU +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/QR +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/SVD +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/StdVector +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv/cxcore.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/calib3d.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/affine.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/base.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/core.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/core_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/cvdef.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/mat.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/matx.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/operations.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/optim.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/traits.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/types.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/types_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/utility.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/version.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/features2d.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/flann/config.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/flann/defines.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/highgui.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/imgproc.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/ml.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/objdetect.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/opencv.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/photo.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/video.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/videoio.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + +src/CMakeFiles/myslam.dir/frame.cpp.o: ../include/myslam/camera.h +src/CMakeFiles/myslam.dir/frame.cpp.o: ../include/myslam/common_include.h +src/CMakeFiles/myslam.dir/frame.cpp.o: ../include/myslam/frame.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +src/CMakeFiles/myslam.dir/frame.cpp.o: ../src/frame.cpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Cholesky +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Core +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Geometry +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Householder +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Jacobi +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/LU +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/QR +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/SVD +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/StdVector +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv/cxcore.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/calib3d.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/affine.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/base.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/core.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/core_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/cvdef.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/mat.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/matx.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/operations.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/optim.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/traits.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/types.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/types_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/utility.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/version.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/features2d.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/flann/config.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/flann/defines.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/highgui.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/imgproc.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/ml.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/objdetect.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/opencv.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/photo.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/video.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/videoio.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + +src/CMakeFiles/myslam.dir/map.cpp.o: ../include/myslam/camera.h +src/CMakeFiles/myslam.dir/map.cpp.o: ../include/myslam/common_include.h +src/CMakeFiles/myslam.dir/map.cpp.o: ../include/myslam/frame.h +src/CMakeFiles/myslam.dir/map.cpp.o: ../include/myslam/map.h +src/CMakeFiles/myslam.dir/map.cpp.o: ../include/myslam/mappoint.h +src/CMakeFiles/myslam.dir/map.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +src/CMakeFiles/myslam.dir/map.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +src/CMakeFiles/myslam.dir/map.cpp.o: ../src/map.cpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Cholesky +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Core +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Geometry +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Householder +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Jacobi +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/LU +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/QR +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/SVD +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/StdVector +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv/cxcore.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/calib3d.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/affine.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/base.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/core.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/core_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/cvdef.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/mat.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/matx.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/operations.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/optim.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/traits.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/types.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/types_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/utility.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/version.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/features2d.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/flann/config.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/flann/defines.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/highgui.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/imgproc.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/ml.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/objdetect.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/opencv.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/photo.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/video.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/videoio.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + +src/CMakeFiles/myslam.dir/mappoint.cpp.o: ../include/myslam/common_include.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: ../include/myslam/mappoint.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: ../src/mappoint.cpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Cholesky +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Core +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Geometry +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Householder +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Jacobi +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/LU +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/QR +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/SVD +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/StdVector +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv/cxcore.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/calib3d.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/affine.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/base.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/core.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/core_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/cvdef.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/mat.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/matx.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/operations.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/optim.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/traits.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/types.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/types_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/utility.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/version.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/features2d.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/flann/config.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/flann/defines.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/highgui.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/imgproc.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/ml.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/objdetect.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/opencv.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/photo.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/video.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/videoio.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + diff --git a/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/flags.make b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/flags.make new file mode 100644 index 00000000..0a67156c --- /dev/null +++ b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/flags.make @@ -0,0 +1,8 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# compile CXX with g++ +CXX_FLAGS = -std=c++11 -march=native -O3 -O3 -DNDEBUG -fPIC -I/usr/include/eigen3 -I/usr/local/include/opencv -I/usr/local/include -I/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus -I"/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/include" + +CXX_DEFINES = -Dmyslam_EXPORTS + diff --git a/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/frame.cpp.o b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/frame.cpp.o new file mode 100644 index 00000000..588f9de5 Binary files /dev/null and b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/frame.cpp.o differ diff --git a/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/link.txt b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/link.txt new file mode 100644 index 00000000..c7dea010 --- /dev/null +++ b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/link.txt @@ -0,0 +1 @@ +g++ -fPIC -std=c++11 -march=native -O3 -O3 -DNDEBUG -shared -Wl,-soname,libmyslam.so -o ../../lib/libmyslam.so CMakeFiles/myslam.dir/frame.cpp.o CMakeFiles/myslam.dir/mappoint.cpp.o CMakeFiles/myslam.dir/map.cpp.o CMakeFiles/myslam.dir/camera.cpp.o CMakeFiles/myslam.dir/config.cpp.o /usr/local/lib/libopencv_viz.so.3.1.0 /usr/local/lib/libopencv_videostab.so.3.1.0 /usr/local/lib/libopencv_videoio.so.3.1.0 /usr/local/lib/libopencv_video.so.3.1.0 /usr/local/lib/libopencv_superres.so.3.1.0 /usr/local/lib/libopencv_stitching.so.3.1.0 /usr/local/lib/libopencv_shape.so.3.1.0 /usr/local/lib/libopencv_photo.so.3.1.0 /usr/local/lib/libopencv_objdetect.so.3.1.0 /usr/local/lib/libopencv_ml.so.3.1.0 /usr/local/lib/libopencv_imgproc.so.3.1.0 /usr/local/lib/libopencv_imgcodecs.so.3.1.0 /usr/local/lib/libopencv_highgui.so.3.1.0 /usr/local/lib/libopencv_flann.so.3.1.0 /usr/local/lib/libopencv_features2d.so.3.1.0 /usr/local/lib/libopencv_core.so.3.1.0 /usr/local/lib/libopencv_calib3d.so.3.1.0 /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build/libSophus.so -lg2o_core -lg2o_stuff -lg2o_types_sba /usr/local/lib/libopencv_features2d.so.3.1.0 /usr/local/lib/libopencv_ml.so.3.1.0 /usr/local/lib/libopencv_highgui.so.3.1.0 /usr/local/lib/libopencv_videoio.so.3.1.0 /usr/local/lib/libopencv_imgcodecs.so.3.1.0 /usr/local/lib/libopencv_flann.so.3.1.0 /usr/local/lib/libopencv_video.so.3.1.0 /usr/local/lib/libopencv_imgproc.so.3.1.0 /usr/local/lib/libopencv_core.so.3.1.0 -Wl,-rpath,/usr/local/lib:/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build diff --git a/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/map.cpp.o b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/map.cpp.o new file mode 100644 index 00000000..c19116e7 Binary files /dev/null and b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/map.cpp.o differ diff --git a/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/mappoint.cpp.o b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/mappoint.cpp.o new file mode 100644 index 00000000..ca9d22de Binary files /dev/null and b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/mappoint.cpp.o differ diff --git a/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/progress.make b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/progress.make new file mode 100644 index 00000000..33e6bffb --- /dev/null +++ b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/myslam.dir/progress.make @@ -0,0 +1,6 @@ +CMAKE_PROGRESS_1 = 1 +CMAKE_PROGRESS_2 = 2 +CMAKE_PROGRESS_3 = 3 +CMAKE_PROGRESS_4 = 4 +CMAKE_PROGRESS_5 = 5 + diff --git a/vSLAM/ch9 project/0.1/build/src/CMakeFiles/progress.marks b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/progress.marks new file mode 100644 index 00000000..7ed6ff82 --- /dev/null +++ b/vSLAM/ch9 project/0.1/build/src/CMakeFiles/progress.marks @@ -0,0 +1 @@ +5 diff --git a/vSLAM/ch9 project/0.1/build/src/Makefile b/vSLAM/ch9 project/0.1/build/src/Makefile new file mode 100644 index 00000000..de78129a --- /dev/null +++ b/vSLAM/ch9 project/0.1/build/src/Makefile @@ -0,0 +1,272 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Default target executed when no arguments are given to make. +default_target: all +.PHONY : default_target + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1" + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" + +#============================================================================= +# Targets provided globally by CMake. + +# Special rule for the target edit_cache +edit_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running interactive CMake command-line interface..." + /usr/bin/cmake -i . +.PHONY : edit_cache + +# Special rule for the target edit_cache +edit_cache/fast: edit_cache +.PHONY : edit_cache/fast + +# Special rule for the target rebuild_cache +rebuild_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake to regenerate build system..." + /usr/bin/cmake -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) +.PHONY : rebuild_cache + +# Special rule for the target rebuild_cache +rebuild_cache/fast: rebuild_cache +.PHONY : rebuild_cache/fast + +# The main all target +all: cmake_check_build_system + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/src/CMakeFiles/progress.marks" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(MAKE) -f CMakeFiles/Makefile2 src/all + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles" 0 +.PHONY : all + +# The main clean target +clean: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(MAKE) -f CMakeFiles/Makefile2 src/clean +.PHONY : clean + +# The main clean target +clean/fast: clean +.PHONY : clean/fast + +# Prepare targets for installation. +preinstall: all + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(MAKE) -f CMakeFiles/Makefile2 src/preinstall +.PHONY : preinstall + +# Prepare targets for installation. +preinstall/fast: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(MAKE) -f CMakeFiles/Makefile2 src/preinstall +.PHONY : preinstall/fast + +# clear depends +depend: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 1 +.PHONY : depend + +# Convenience name for target. +src/CMakeFiles/myslam.dir/rule: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(MAKE) -f CMakeFiles/Makefile2 src/CMakeFiles/myslam.dir/rule +.PHONY : src/CMakeFiles/myslam.dir/rule + +# Convenience name for target. +myslam: src/CMakeFiles/myslam.dir/rule +.PHONY : myslam + +# fast build rule for target. +myslam/fast: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/build +.PHONY : myslam/fast + +camera.o: camera.cpp.o +.PHONY : camera.o + +# target to build an object file +camera.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/camera.cpp.o +.PHONY : camera.cpp.o + +camera.i: camera.cpp.i +.PHONY : camera.i + +# target to preprocess a source file +camera.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/camera.cpp.i +.PHONY : camera.cpp.i + +camera.s: camera.cpp.s +.PHONY : camera.s + +# target to generate assembly for a file +camera.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/camera.cpp.s +.PHONY : camera.cpp.s + +config.o: config.cpp.o +.PHONY : config.o + +# target to build an object file +config.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/config.cpp.o +.PHONY : config.cpp.o + +config.i: config.cpp.i +.PHONY : config.i + +# target to preprocess a source file +config.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/config.cpp.i +.PHONY : config.cpp.i + +config.s: config.cpp.s +.PHONY : config.s + +# target to generate assembly for a file +config.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/config.cpp.s +.PHONY : config.cpp.s + +frame.o: frame.cpp.o +.PHONY : frame.o + +# target to build an object file +frame.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/frame.cpp.o +.PHONY : frame.cpp.o + +frame.i: frame.cpp.i +.PHONY : frame.i + +# target to preprocess a source file +frame.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/frame.cpp.i +.PHONY : frame.cpp.i + +frame.s: frame.cpp.s +.PHONY : frame.s + +# target to generate assembly for a file +frame.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/frame.cpp.s +.PHONY : frame.cpp.s + +map.o: map.cpp.o +.PHONY : map.o + +# target to build an object file +map.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/map.cpp.o +.PHONY : map.cpp.o + +map.i: map.cpp.i +.PHONY : map.i + +# target to preprocess a source file +map.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/map.cpp.i +.PHONY : map.cpp.i + +map.s: map.cpp.s +.PHONY : map.s + +# target to generate assembly for a file +map.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/map.cpp.s +.PHONY : map.cpp.s + +mappoint.o: mappoint.cpp.o +.PHONY : mappoint.o + +# target to build an object file +mappoint.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/mappoint.cpp.o +.PHONY : mappoint.cpp.o + +mappoint.i: mappoint.cpp.i +.PHONY : mappoint.i + +# target to preprocess a source file +mappoint.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/mappoint.cpp.i +.PHONY : mappoint.cpp.i + +mappoint.s: mappoint.cpp.s +.PHONY : mappoint.s + +# target to generate assembly for a file +mappoint.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/mappoint.cpp.s +.PHONY : mappoint.cpp.s + +# Help Target +help: + @echo "The following are some of the valid targets for this Makefile:" + @echo "... all (the default if no target is provided)" + @echo "... clean" + @echo "... depend" + @echo "... edit_cache" + @echo "... myslam" + @echo "... rebuild_cache" + @echo "... camera.o" + @echo "... camera.i" + @echo "... camera.s" + @echo "... config.o" + @echo "... config.i" + @echo "... config.s" + @echo "... frame.o" + @echo "... frame.i" + @echo "... frame.s" + @echo "... map.o" + @echo "... map.i" + @echo "... map.s" + @echo "... mappoint.o" + @echo "... mappoint.i" + @echo "... mappoint.s" +.PHONY : help + + + +#============================================================================= +# Special targets to cleanup operation of make. + +# Special rule to run CMake to check the build system integrity. +# No rule that depends on this can have commands that come from listfiles +# because they might be regenerated. +cmake_check_build_system: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0 +.PHONY : cmake_check_build_system + diff --git a/vSLAM/ch9 project/0.1/build/src/cmake_install.cmake b/vSLAM/ch9 project/0.1/build/src/cmake_install.cmake new file mode 100644 index 00000000..0330f13f --- /dev/null +++ b/vSLAM/ch9 project/0.1/build/src/cmake_install.cmake @@ -0,0 +1,34 @@ +# Install script for directory: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/src + +# Set the install prefix +IF(NOT DEFINED CMAKE_INSTALL_PREFIX) + SET(CMAKE_INSTALL_PREFIX "/usr/local") +ENDIF(NOT DEFINED CMAKE_INSTALL_PREFIX) +STRING(REGEX REPLACE "/$" "" CMAKE_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}") + +# Set the install configuration name. +IF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + IF(BUILD_TYPE) + STRING(REGEX REPLACE "^[^A-Za-z0-9_]+" "" + CMAKE_INSTALL_CONFIG_NAME "${BUILD_TYPE}") + ELSE(BUILD_TYPE) + SET(CMAKE_INSTALL_CONFIG_NAME "Release") + ENDIF(BUILD_TYPE) + MESSAGE(STATUS "Install configuration: \"${CMAKE_INSTALL_CONFIG_NAME}\"") +ENDIF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + +# Set the component getting installed. +IF(NOT CMAKE_INSTALL_COMPONENT) + IF(COMPONENT) + MESSAGE(STATUS "Install component: \"${COMPONENT}\"") + SET(CMAKE_INSTALL_COMPONENT "${COMPONENT}") + ELSE(COMPONENT) + SET(CMAKE_INSTALL_COMPONENT) + ENDIF(COMPONENT) +ENDIF(NOT CMAKE_INSTALL_COMPONENT) + +# Install shared libraries without execute permission? +IF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + SET(CMAKE_INSTALL_SO_NO_EXE "1") +ENDIF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + diff --git a/vSLAM/ch9 project/0.1/build/test/CMakeFiles/CMakeDirectoryInformation.cmake b/vSLAM/ch9 project/0.1/build/test/CMakeFiles/CMakeDirectoryInformation.cmake new file mode 100644 index 00000000..e7e829c5 --- /dev/null +++ b/vSLAM/ch9 project/0.1/build/test/CMakeFiles/CMakeDirectoryInformation.cmake @@ -0,0 +1,16 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Relative path conversion top directories. +SET(CMAKE_RELATIVE_PATH_TOP_SOURCE "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1") +SET(CMAKE_RELATIVE_PATH_TOP_BINARY "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build") + +# Force unix paths in dependencies. +SET(CMAKE_FORCE_UNIX_PATHS 1) + + +# The C and CXX include file regular expressions for this directory. +SET(CMAKE_C_INCLUDE_REGEX_SCAN "^.*$") +SET(CMAKE_C_INCLUDE_REGEX_COMPLAIN "^$") +SET(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN}) +SET(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN}) diff --git a/vSLAM/ch9 project/0.1/build/test/CMakeFiles/progress.marks b/vSLAM/ch9 project/0.1/build/test/CMakeFiles/progress.marks new file mode 100644 index 00000000..573541ac --- /dev/null +++ b/vSLAM/ch9 project/0.1/build/test/CMakeFiles/progress.marks @@ -0,0 +1 @@ +0 diff --git a/vSLAM/ch9 project/0.1/build/test/Makefile b/vSLAM/ch9 project/0.1/build/test/Makefile new file mode 100644 index 00000000..c385469a --- /dev/null +++ b/vSLAM/ch9 project/0.1/build/test/Makefile @@ -0,0 +1,122 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Default target executed when no arguments are given to make. +default_target: all +.PHONY : default_target + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1" + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" + +#============================================================================= +# Targets provided globally by CMake. + +# Special rule for the target edit_cache +edit_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running interactive CMake command-line interface..." + /usr/bin/cmake -i . +.PHONY : edit_cache + +# Special rule for the target edit_cache +edit_cache/fast: edit_cache +.PHONY : edit_cache/fast + +# Special rule for the target rebuild_cache +rebuild_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake to regenerate build system..." + /usr/bin/cmake -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) +.PHONY : rebuild_cache + +# Special rule for the target rebuild_cache +rebuild_cache/fast: rebuild_cache +.PHONY : rebuild_cache/fast + +# The main all target +all: cmake_check_build_system + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/test/CMakeFiles/progress.marks" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(MAKE) -f CMakeFiles/Makefile2 test/all + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build/CMakeFiles" 0 +.PHONY : all + +# The main clean target +clean: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(MAKE) -f CMakeFiles/Makefile2 test/clean +.PHONY : clean + +# The main clean target +clean/fast: clean +.PHONY : clean/fast + +# Prepare targets for installation. +preinstall: all + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(MAKE) -f CMakeFiles/Makefile2 test/preinstall +.PHONY : preinstall + +# Prepare targets for installation. +preinstall/fast: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(MAKE) -f CMakeFiles/Makefile2 test/preinstall +.PHONY : preinstall/fast + +# clear depends +depend: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 1 +.PHONY : depend + +# Help Target +help: + @echo "The following are some of the valid targets for this Makefile:" + @echo "... all (the default if no target is provided)" + @echo "... clean" + @echo "... depend" + @echo "... edit_cache" + @echo "... rebuild_cache" +.PHONY : help + + + +#============================================================================= +# Special targets to cleanup operation of make. + +# Special rule to run CMake to check the build system integrity. +# No rule that depends on this can have commands that come from listfiles +# because they might be regenerated. +cmake_check_build_system: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/build" && $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0 +.PHONY : cmake_check_build_system + diff --git a/vSLAM/ch9 project/0.1/build/test/cmake_install.cmake b/vSLAM/ch9 project/0.1/build/test/cmake_install.cmake new file mode 100644 index 00000000..d3fa50a6 --- /dev/null +++ b/vSLAM/ch9 project/0.1/build/test/cmake_install.cmake @@ -0,0 +1,34 @@ +# Install script for directory: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.1/test + +# Set the install prefix +IF(NOT DEFINED CMAKE_INSTALL_PREFIX) + SET(CMAKE_INSTALL_PREFIX "/usr/local") +ENDIF(NOT DEFINED CMAKE_INSTALL_PREFIX) +STRING(REGEX REPLACE "/$" "" CMAKE_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}") + +# Set the install configuration name. +IF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + IF(BUILD_TYPE) + STRING(REGEX REPLACE "^[^A-Za-z0-9_]+" "" + CMAKE_INSTALL_CONFIG_NAME "${BUILD_TYPE}") + ELSE(BUILD_TYPE) + SET(CMAKE_INSTALL_CONFIG_NAME "Release") + ENDIF(BUILD_TYPE) + MESSAGE(STATUS "Install configuration: \"${CMAKE_INSTALL_CONFIG_NAME}\"") +ENDIF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + +# Set the component getting installed. +IF(NOT CMAKE_INSTALL_COMPONENT) + IF(COMPONENT) + MESSAGE(STATUS "Install component: \"${COMPONENT}\"") + SET(CMAKE_INSTALL_COMPONENT "${COMPONENT}") + ELSE(COMPONENT) + SET(CMAKE_INSTALL_COMPONENT) + ENDIF(COMPONENT) +ENDIF(NOT CMAKE_INSTALL_COMPONENT) + +# Install shared libraries without execute permission? +IF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + SET(CMAKE_INSTALL_SO_NO_EXE "1") +ENDIF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + diff --git a/vSLAM/ch9 project/0.1/cmake_modules/FindCSparse.cmake b/vSLAM/ch9 project/0.1/cmake_modules/FindCSparse.cmake new file mode 100644 index 00000000..f31df8de --- /dev/null +++ b/vSLAM/ch9 project/0.1/cmake_modules/FindCSparse.cmake @@ -0,0 +1,25 @@ +# Look for csparse; note the difference in the directory specifications! +FIND_PATH(CSPARSE_INCLUDE_DIR NAMES cs.h + PATHS + /usr/include/suitesparse + /usr/include + /opt/local/include + /usr/local/include + /sw/include + /usr/include/ufsparse + /opt/local/include/ufsparse + /usr/local/include/ufsparse + /sw/include/ufsparse + ) + +FIND_LIBRARY(CSPARSE_LIBRARY NAMES cxsparse + PATHS + /usr/lib + /usr/local/lib + /opt/local/lib + /sw/lib + ) + +include(FindPackageHandleStandardArgs) +find_package_handle_standard_args(CSPARSE DEFAULT_MSG + CSPARSE_INCLUDE_DIR CSPARSE_LIBRARY) diff --git a/vSLAM/ch9 project/0.1/cmake_modules/FindG2O.cmake b/vSLAM/ch9 project/0.1/cmake_modules/FindG2O.cmake new file mode 100644 index 00000000..655600fb --- /dev/null +++ b/vSLAM/ch9 project/0.1/cmake_modules/FindG2O.cmake @@ -0,0 +1,113 @@ +# Find the header files + +FIND_PATH(G2O_INCLUDE_DIR g2o/core/base_vertex.h + ${G2O_ROOT}/include + $ENV{G2O_ROOT}/include + $ENV{G2O_ROOT} + /usr/local/include + /usr/include + /opt/local/include + /sw/local/include + /sw/include + NO_DEFAULT_PATH + ) + +# Macro to unify finding both the debug and release versions of the +# libraries; this is adapted from the OpenSceneGraph FIND_LIBRARY +# macro. + +MACRO(FIND_G2O_LIBRARY MYLIBRARY MYLIBRARYNAME) + + FIND_LIBRARY("${MYLIBRARY}_DEBUG" + NAMES "g2o_${MYLIBRARYNAME}_d" + PATHS + ${G2O_ROOT}/lib/Debug + ${G2O_ROOT}/lib + $ENV{G2O_ROOT}/lib/Debug + $ENV{G2O_ROOT}/lib + NO_DEFAULT_PATH + ) + + FIND_LIBRARY("${MYLIBRARY}_DEBUG" + NAMES "g2o_${MYLIBRARYNAME}_d" + PATHS + ~/Library/Frameworks + /Library/Frameworks + /usr/local/lib + /usr/local/lib64 + /usr/lib + /usr/lib64 + /opt/local/lib + /sw/local/lib + /sw/lib + ) + + FIND_LIBRARY(${MYLIBRARY} + NAMES "g2o_${MYLIBRARYNAME}" + PATHS + ${G2O_ROOT}/lib/Release + ${G2O_ROOT}/lib + $ENV{G2O_ROOT}/lib/Release + $ENV{G2O_ROOT}/lib + NO_DEFAULT_PATH + ) + + FIND_LIBRARY(${MYLIBRARY} + NAMES "g2o_${MYLIBRARYNAME}" + PATHS + ~/Library/Frameworks + /Library/Frameworks + /usr/local/lib + /usr/local/lib64 + /usr/lib + /usr/lib64 + /opt/local/lib + /sw/local/lib + /sw/lib + ) + + IF(NOT ${MYLIBRARY}_DEBUG) + IF(MYLIBRARY) + SET(${MYLIBRARY}_DEBUG ${MYLIBRARY}) + ENDIF(MYLIBRARY) + ENDIF( NOT ${MYLIBRARY}_DEBUG) + +ENDMACRO(FIND_G2O_LIBRARY LIBRARY LIBRARYNAME) + +# Find the core elements +FIND_G2O_LIBRARY(G2O_STUFF_LIBRARY stuff) +FIND_G2O_LIBRARY(G2O_CORE_LIBRARY core) + +# Find the CLI library +FIND_G2O_LIBRARY(G2O_CLI_LIBRARY cli) + +# Find the pluggable solvers +FIND_G2O_LIBRARY(G2O_SOLVER_CHOLMOD solver_cholmod) +FIND_G2O_LIBRARY(G2O_SOLVER_CSPARSE solver_csparse) +FIND_G2O_LIBRARY(G2O_SOLVER_CSPARSE_EXTENSION csparse_extension) +FIND_G2O_LIBRARY(G2O_SOLVER_DENSE solver_dense) +FIND_G2O_LIBRARY(G2O_SOLVER_PCG solver_pcg) +FIND_G2O_LIBRARY(G2O_SOLVER_SLAM2D_LINEAR solver_slam2d_linear) +FIND_G2O_LIBRARY(G2O_SOLVER_STRUCTURE_ONLY solver_structure_only) +FIND_G2O_LIBRARY(G2O_SOLVER_EIGEN solver_eigen) + +# Find the predefined types +FIND_G2O_LIBRARY(G2O_TYPES_DATA types_data) +FIND_G2O_LIBRARY(G2O_TYPES_ICP types_icp) +FIND_G2O_LIBRARY(G2O_TYPES_SBA types_sba) +FIND_G2O_LIBRARY(G2O_TYPES_SCLAM2D types_sclam2d) +FIND_G2O_LIBRARY(G2O_TYPES_SIM3 types_sim3) +FIND_G2O_LIBRARY(G2O_TYPES_SLAM2D types_slam2d) +FIND_G2O_LIBRARY(G2O_TYPES_SLAM3D types_slam3d) + +# G2O solvers declared found if we found at least one solver +SET(G2O_SOLVERS_FOUND "NO") +IF(G2O_SOLVER_CHOLMOD OR G2O_SOLVER_CSPARSE OR G2O_SOLVER_DENSE OR G2O_SOLVER_PCG OR G2O_SOLVER_SLAM2D_LINEAR OR G2O_SOLVER_STRUCTURE_ONLY OR G2O_SOLVER_EIGEN) + SET(G2O_SOLVERS_FOUND "YES") +ENDIF(G2O_SOLVER_CHOLMOD OR G2O_SOLVER_CSPARSE OR G2O_SOLVER_DENSE OR G2O_SOLVER_PCG OR G2O_SOLVER_SLAM2D_LINEAR OR G2O_SOLVER_STRUCTURE_ONLY OR G2O_SOLVER_EIGEN) + +# G2O itself declared found if we found the core libraries and at least one solver +SET(G2O_FOUND "NO") +IF(G2O_STUFF_LIBRARY AND G2O_CORE_LIBRARY AND G2O_INCLUDE_DIR AND G2O_SOLVERS_FOUND) + SET(G2O_FOUND "YES") +ENDIF(G2O_STUFF_LIBRARY AND G2O_CORE_LIBRARY AND G2O_INCLUDE_DIR AND G2O_SOLVERS_FOUND) diff --git a/vSLAM/ch9 project/0.1/config/default.yaml b/vSLAM/ch9 project/0.1/config/default.yaml new file mode 100644 index 00000000..1e1150bf --- /dev/null +++ b/vSLAM/ch9 project/0.1/config/default.yaml @@ -0,0 +1,13 @@ +%YAML:1.0 +# data +# the tum dataset directory, change it to yours! +dataset_dir: /home/ciang/dataset/rgbd_dataset_freiburg1_xyz + +# camera intrinsics +# fr1 +camera.fx: 517.3 +camera.fy: 516.5 +camera.cx: 325.1 +camera.cy: 249.7 + +camera.depth_scale: 5000 \ No newline at end of file diff --git a/vSLAM/ch9 project/0.1/include/myslam/camera.h b/vSLAM/ch9 project/0.1/include/myslam/camera.h new file mode 100644 index 00000000..7548bd3b --- /dev/null +++ b/vSLAM/ch9 project/0.1/include/myslam/camera.h @@ -0,0 +1,52 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +// 相机模型类 +#ifndef CAMERA_H //防止头文件重复引用 +#define CAMERA_H//宏定义 + +#include "myslam/common_include.h"//常用的头文件 放在一起 化繁为简 + +namespace myslam//命令空间下 防止定义的出其他库里的同名函数 +{ + +// Pinhole RGBD camera model +class Camera//相机模型类 +{ +public://数据成员设置为共有 可以改成私有 private + typedef std::shared_ptr Ptr;//共享指针 把 智能指针定义成 Camera的指针类型 以后参数传递时 使用Camera::Ptr 类型就可以了 + float fx_, fy_, cx_, cy_, depth_scale_; // Camera intrinsics 相机内参数 + + Camera(); + Camera ( float fx, float fy, float cx, float cy, float depth_scale=0 ) : + fx_ ( fx ), fy_ ( fy ), cx_ ( cx ), cy_ ( cy ), depth_scale_ ( depth_scale ) + {} + + // 坐标转换 coordinate transform: world, camera, pixel + //使用 Sophus::SE3 类表达相机位姿态(相机外参数) 即转换矩阵 + Vector3d world2camera( const Vector3d& p_w, const SE3& T_c_w );//世界坐标系(3维 ) 到 相机坐标系 输入 世界坐标系坐标p_w 和 T_c_w 转换矩阵 + Vector3d camera2world( const Vector3d& p_c, const SE3& T_c_w ); //相机坐标系 到 世界坐标系 输入 相机坐标系坐标p_c 和 T_c_w 转换矩阵 + Vector2d camera2pixel( const Vector3d& p_c ); //相机坐标系 到 图像像素坐标系 使用相机内参数 + Vector3d pixel2camera( const Vector2d& p_p, double depth=1 ); //图像像素坐标系(两维) 到 相机坐标系 使用相机内参数 + Vector3d pixel2world ( const Vector2d& p_p, const SE3& T_c_w, double depth=1 );//图像像素坐标系(两维) 到 世界坐标系pixel2camera2world + Vector2d world2pixel ( const Vector3d& p_w, const SE3& T_c_w ); //世界坐标系(三维) 到 图像像素坐标系 world2camera2pixel + +}; + +} +#endif // CAMERA_H diff --git a/vSLAM/ch9 project/0.1/include/myslam/common_include.h b/vSLAM/ch9 project/0.1/include/myslam/common_include.h new file mode 100644 index 00000000..9ff89547 --- /dev/null +++ b/vSLAM/ch9 project/0.1/include/myslam/common_include.h @@ -0,0 +1,50 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + + +#ifndef COMMON_INCLUDE_H +#define COMMON_INCLUDE_H + +// define the commonly included file to avoid a long include list +// for Eigen +#include +#include +using Eigen::Vector2d; +using Eigen::Vector3d; + +// for Sophus +#include +using Sophus::SE3; + +// for cv +#include +using cv::Mat; + +// std +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace std; +#endif \ No newline at end of file diff --git a/vSLAM/ch9 project/0.1/include/myslam/config.h b/vSLAM/ch9 project/0.1/include/myslam/config.h new file mode 100644 index 00000000..1af029f5 --- /dev/null +++ b/vSLAM/ch9 project/0.1/include/myslam/config.h @@ -0,0 +1,50 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +/*提供配置参数 */ +#ifndef CONFIG_H //防止头文件重复引用 +#define CONFIG_H//宏定义 + +#include "myslam/common_include.h" + +namespace myslam //命令空间下 防止定义的出其他库里的同名函数 +{ +class Config +{ +private://私有对象 + static std::shared_ptr config_; //共享指针 把 智能指针定义成 Config的指针类型 以后参数传递时 使用Config:Ptr 类型就可以了 + cv::FileStorage file_;//使用 opencv提供的FileStorage类 读取一个YAML文件 可以通过模板函数get 获取任意类型的参数值 + + Config () {} // private constructor makes a singleton +public: + ~Config(); // close the file when deconstructing + + // 读取一个参数文件 set a new config file + static void setParameterFile( const std::string& filename ); + + // access the parameter values + //获取参数的值 + template< typename T > + static T get( const std::string& key )//可以通过模板函数get 获取任意类型的参数值 + { + return T( Config::config_->file_[key] ); + } +}; +} + +#endif // CONFIG_H diff --git a/vSLAM/ch9 project/0.1/include/myslam/frame.h b/vSLAM/ch9 project/0.1/include/myslam/frame.h new file mode 100644 index 00000000..adafc506 --- /dev/null +++ b/vSLAM/ch9 project/0.1/include/myslam/frame.h @@ -0,0 +1,61 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifndef FRAME_H //防止头文件重复引用 +#define FRAME_H//宏定义 + +#include "myslam/common_include.h" +#include "myslam/camera.h" +// 视频图像 帧 类 +namespace myslam //命令空间下 防止定义的出其他库里的同名函数 +{ + +// forward declare +class MapPoint;// 使用 特征点/路标点 类 +class Frame // 视频图像 帧 类 +{ +public:// + typedef std::shared_ptr Ptr;//共享指针 把 智能指针定义成 Frame的指针类型 以后参数传递时 使用Frame::Ptr 类型就可以了 + unsigned long id_; // id of this frame 标号 编号 + double time_stamp_; // when it is recorded 时间戳 记录 + SE3 T_c_w_; // transform from world to camera w2c坐标变换 + Camera::Ptr camera_; // Pinhole RGBD Camera model 使用相机模型 Camera::Ptr + Mat color_, depth_; // color and depth image 彩色图 深度图 + +public: // data members 数据成员设置为公有 可以改成私有 private + Frame(); + Frame( long id, double time_stamp=0, SE3 T_c_w=SE3(), Camera::Ptr camera=nullptr, Mat color=Mat(), Mat depth=Mat() ); + ~Frame(); + + // factory function + static Frame::Ptr createFrame(); + + // find the depth in depth map + double findDepth( const cv::KeyPoint& kp ); + + // Get Camera Center + Vector3d getCamCenter() const; + + // check if a point is in this frame + bool isInFrame( const Vector3d& pt_world ); +}; + +} + +#endif // FRAME_H diff --git a/vSLAM/ch9 project/0.1/include/myslam/map.h b/vSLAM/ch9 project/0.1/include/myslam/map.h new file mode 100644 index 00000000..a735fd82 --- /dev/null +++ b/vSLAM/ch9 project/0.1/include/myslam/map.h @@ -0,0 +1,43 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +/*管理 特征点/路标 保存所有的特征点/路标 和关键帧*/ +#ifndef MAP_H//防止头文件重复引用 +#define MAP_H//宏定义 + +#include "myslam/common_include.h" +#include "myslam/frame.h" +#include "myslam/mappoint.h"//特征点/路标 + +namespace myslam//命令空间下 防止定义的出其他库里的同名函数 +{ +class Map//类 +{ +public: + typedef shared_ptr Ptr;//共享指针 把 智能指针定义成 Map的指针类型 以后参数传递时 使用Map::Ptr 类型就可以了 + unordered_map map_points_; // all landmarks 所有的路标/特征点 + unordered_map keyframes_; // all key-frames 所有的关键帧 + + Map() {} + //需要随机访问 使用散列(Hash) 来存储 + void insertKeyFrame( Frame::Ptr frame ); //保存/插入 关键帧 + void insertMapPoint( MapPoint::Ptr map_point ); //保存/插入 路标/特征点 +}; +} + +#endif // MAP_H diff --git a/vSLAM/ch9 project/0.1/include/myslam/mappoint.h b/vSLAM/ch9 project/0.1/include/myslam/mappoint.h new file mode 100644 index 00000000..1edd90f0 --- /dev/null +++ b/vSLAM/ch9 project/0.1/include/myslam/mappoint.h @@ -0,0 +1,46 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +/*特征点/路标*/ +#ifndef MAPPOINT_H//防止头文件重复引用 +#define MAPPOINT_H//宏定义 + +namespace myslam//命令空间下 防止定义的出其他库里的同名函数 +{ + +class Frame; +class MapPoint//类 +{ +public: + typedef shared_ptr Ptr;//共享指针 把 智能指针定义成 MapPoint的指针类型 以后参数传递时 使用MapPoint::Ptr 类型就可以了 + unsigned long id_; // ID 标号 + Vector3d pos_; // Position in world 世界坐标系下的位置坐标 (x y z) + Vector3d norm_; // Normal of viewing direction 方向 + Mat descriptor_; // Descriptor for matching 描述子 + int observed_times_; // being observed by feature matching algo. 特征匹配时的时间 + int correct_times_; // being an inliner in pose estimation + + MapPoint(); + MapPoint( long id, Vector3d position, Vector3d norm ); + + // factory function + static MapPoint::Ptr createMapPoint(); +}; +} + +#endif // MAPPOINT_H diff --git a/vSLAM/ch9 project/0.1/include/myslam/visual_odometry.h b/vSLAM/ch9 project/0.1/include/myslam/visual_odometry.h new file mode 100644 index 00000000..fbed90cf --- /dev/null +++ b/vSLAM/ch9 project/0.1/include/myslam/visual_odometry.h @@ -0,0 +1 @@ +//空 \ No newline at end of file diff --git a/vSLAM/ch9 project/0.1/lib/liblibmyslam.a b/vSLAM/ch9 project/0.1/lib/liblibmyslam.a new file mode 100644 index 00000000..46f62f98 Binary files /dev/null and b/vSLAM/ch9 project/0.1/lib/liblibmyslam.a differ diff --git a/vSLAM/ch9 project/0.1/lib/libmyslam.so b/vSLAM/ch9 project/0.1/lib/libmyslam.so new file mode 100755 index 00000000..b3a24ecb Binary files /dev/null and b/vSLAM/ch9 project/0.1/lib/libmyslam.so differ diff --git a/vSLAM/ch9 project/0.1/src/CMakeLists.txt b/vSLAM/ch9 project/0.1/src/CMakeLists.txt new file mode 100644 index 00000000..f0c2cf40 --- /dev/null +++ b/vSLAM/ch9 project/0.1/src/CMakeLists.txt @@ -0,0 +1,11 @@ +add_library( myslam SHARED + frame.cpp + mappoint.cpp + map.cpp + camera.cpp + config.cpp +) + +target_link_libraries( myslam + ${THIRD_PARTY_LIBS} +) diff --git a/vSLAM/ch9 project/0.1/src/camera.cpp b/vSLAM/ch9 project/0.1/src/camera.cpp new file mode 100644 index 00000000..a4713097 --- /dev/null +++ b/vSLAM/ch9 project/0.1/src/camera.cpp @@ -0,0 +1,76 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "myslam/camera.h" + +namespace myslam +{ + +Camera::Camera() +{ +} +//使用 Sophus::SE3 类表达相机位姿态(相机外参数) 即转换矩阵 + +/*******使用相机外参数********/ +//世界坐标系(3维 ) 到 相机坐标系 +//输入 世界坐标系坐标 和 T_c_w 转换矩阵 +Vector3d Camera::world2camera ( const Vector3d& p_w, const SE3& T_c_w ) +{ + return T_c_w*p_w; +} +//相机坐标系 到 世界坐标系 +//输入 相机坐标系坐标p_c 和 T_c_w 转换矩阵 +Vector3d Camera::camera2world ( const Vector3d& p_c, const SE3& T_c_w ) +{ + return T_c_w.inverse() *p_c; +} + +/*******使用相机内参数*******/ + //相机坐标系 到 图像像素坐标系 +Vector2d Camera::camera2pixel ( const Vector3d& p_c ) +{ + return Vector2d ( + fx_ * p_c ( 0,0 ) / p_c ( 2,0 ) + cx_, + fy_ * p_c ( 1,0 ) / p_c ( 2,0 ) + cy_ + ); +} +//图像像素坐标系(两维) 到 相机坐标系 使用相机内参数 +Vector3d Camera::pixel2camera ( const Vector2d& p_p, double depth ) +{ + return Vector3d ( + ( p_p ( 0,0 )-cx_ ) *depth/fx_, + ( p_p ( 1,0 )-cy_ ) *depth/fy_, + depth + ); +} + +//世界坐标系(三维) 到 图像像素坐标系 world2camera2pixel +Vector2d Camera::world2pixel ( const Vector3d& p_w, const SE3& T_c_w ) +{ + return camera2pixel ( world2camera ( p_w, T_c_w ) ); +} + +//图像像素坐标系(两维) 到 世界坐标系 pixel2camera2world +Vector3d Camera::pixel2world ( const Vector2d& p_p, const SE3& T_c_w, double depth ) +{ + return camera2world ( pixel2camera ( p_p, depth ), T_c_w ); +} + + +} diff --git a/vSLAM/ch9 project/0.1/src/config.cpp b/vSLAM/ch9 project/0.1/src/config.cpp new file mode 100644 index 00000000..fbfd79d9 --- /dev/null +++ b/vSLAM/ch9 project/0.1/src/config.cpp @@ -0,0 +1,46 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "myslam/config.h" + +namespace myslam //命令空间下 防止定义的出其他库里的同名函数 +{ + // 读取参数文件 +void Config::setParameterFile( const std::string& filename ) +{ + if ( config_ == nullptr ) + config_ = shared_ptr(new Config); + config_->file_ = cv::FileStorage( filename.c_str(), cv::FileStorage::READ );//读文件 + if ( config_->file_.isOpened() == false )//打开文件错误 + { + std::cerr<<"parameter file "<file_.release();//释放 + return; + } +} +//析构函数 退出函数 +Config::~Config() +{ + if ( file_.isOpened() ) + file_.release(); +} + +shared_ptr Config::config_ = nullptr; + +} diff --git a/vSLAM/ch9 project/0.1/src/frame.cpp b/vSLAM/ch9 project/0.1/src/frame.cpp new file mode 100644 index 00000000..4d2ecb12 --- /dev/null +++ b/vSLAM/ch9 project/0.1/src/frame.cpp @@ -0,0 +1,90 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "myslam/frame.h" + +namespace myslam//命令空间下 防止定义的出其他库里的同名函数 +{ +Frame::Frame() +: id_(-1), time_stamp_(-1), camera_(nullptr) +{ + +} + +Frame::Frame ( long id, double time_stamp, SE3 T_c_w, Camera::Ptr camera, Mat color, Mat depth ) +: id_(id), time_stamp_(time_stamp), T_c_w_(T_c_w), camera_(camera), color_(color), depth_(depth) +{ + +} + +Frame::~Frame() +{ + +} + +Frame::Ptr Frame::createFrame() +{ + static long factory_id = 0; + return Frame::Ptr( new Frame(factory_id++) ); +} + +double Frame::findDepth ( const cv::KeyPoint& kp ) +{ + int x = cvRound(kp.pt.x); + int y = cvRound(kp.pt.y); + ushort d = depth_.ptr(y)[x]; + if ( d!=0 ) + { + return double(d)/camera_->depth_scale_; + } + else + { + // check the nearby points + int dx[4] = {-1,0,1,0}; + int dy[4] = {0,-1,0,1}; + for ( int i=0; i<4; i++ ) + { + d = depth_.ptr( y+dy[i] )[x+dx[i]]; + if ( d!=0 ) + { + return double(d)/camera_->depth_scale_; + } + } + } + return -1.0; +} + + +Vector3d Frame::getCamCenter() const +{ + return T_c_w_.inverse().translation(); +} + +bool Frame::isInFrame ( const Vector3d& pt_world ) +{ + Vector3d p_cam = camera_->world2camera( pt_world, T_c_w_ ); + if ( p_cam(2,0)<0 ) + return false; + Vector2d pixel = camera_->world2pixel( pt_world, T_c_w_ ); + return pixel(0,0)>0 && pixel(1,0)>0 + && pixel(0,0) + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "myslam/map.h" + +namespace myslam +{ + +void Map::insertKeyFrame ( Frame::Ptr frame ) +{ + cout<<"Key frame size = "<id_) == keyframes_.end() ) + { + keyframes_.insert( make_pair(frame->id_, frame) ); + } + else + { + keyframes_[ frame->id_ ] = frame; + } +} + +void Map::insertMapPoint ( MapPoint::Ptr map_point ) +{ + if ( map_points_.find(map_point->id_) == map_points_.end() ) + { + map_points_.insert( make_pair(map_point->id_, map_point) ); + } + else + { + map_points_[map_point->id_] = map_point; + } +} + + +} diff --git a/vSLAM/ch9 project/0.1/src/mappoint.cpp b/vSLAM/ch9 project/0.1/src/mappoint.cpp new file mode 100644 index 00000000..77bc33dd --- /dev/null +++ b/vSLAM/ch9 project/0.1/src/mappoint.cpp @@ -0,0 +1,46 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "myslam/common_include.h" +#include "myslam/mappoint.h" + +namespace myslam//命令空间下 防止定义的出其他库里的同名函数 +{ + +MapPoint::MapPoint() +: id_(-1), pos_(Vector3d(0,0,0)), norm_(Vector3d(0,0,0)), observed_times_(0), correct_times_(0) +{ + +} + +MapPoint::MapPoint ( long id, Vector3d position, Vector3d norm ) +: id_(id), pos_(position), norm_(norm), observed_times_(0), correct_times_(0) +{ + +} + +MapPoint::Ptr MapPoint::createMapPoint() +{ + static long factory_id = 0; + return MapPoint::Ptr( + new MapPoint( factory_id++, Vector3d(0,0,0), Vector3d(0,0,0) )//标号+位置+方向 + ); +} + +} diff --git a/vSLAM/ch9 project/0.1/test/CMakeLists.txt b/vSLAM/ch9 project/0.1/test/CMakeLists.txt new file mode 100644 index 00000000..e282b814 --- /dev/null +++ b/vSLAM/ch9 project/0.1/test/CMakeLists.txt @@ -0,0 +1 @@ +#空 \ No newline at end of file diff --git a/vSLAM/ch9 project/0.2/.kdev4/0.2.kdev4 b/vSLAM/ch9 project/0.2/.kdev4/0.2.kdev4 new file mode 100644 index 00000000..c276e49b --- /dev/null +++ b/vSLAM/ch9 project/0.2/.kdev4/0.2.kdev4 @@ -0,0 +1,39 @@ +[Buildset] +BuildItems=@Variant(\x00\x00\x00\t\x00\x00\x00\x00\x01\x00\x00\x00\x0b\x00\x00\x00\x00\x01\x00\x00\x00\x06\x000\x00.\x002) + +[CMake] +Build Directory Count=1 +Current Build Directory Index=0 +ProjectRootRelative=./ + +[CMake][CMake Build Directory 0] +Build Directory Path=file:///home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9%20project/0.2/build +Build Type=Debug +CMake Binary=file:///usr/bin/cmake +Environment Profile= +Extra Arguments= +Install Directory=file:///usr/local + +[Launch] +Launch Configurations=Launch Configuration 0 + +[Launch][Launch Configuration 0] +Configured Launch Modes=execute +Configured Launchers=nativeAppLauncher +Name=新建 应用程序 启动器 +Type=Native Application + +[Launch][Launch Configuration 0][Data] +Arguments=../config/default.yaml +Dependencies=@Variant(\x00\x00\x00\t\x00\x00\x00\x00\x00) +Dependency Action=Nothing +EnvironmentGroup=default +Executable=file:///home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9%20project/0.2/bin/run_vo +External Terminal=konsole --noclose --workdir %workdir -e %exe +Project Target=0.2,test,run_vo +Use External Terminal=false +Working Directory= +isExecutable=true + +[Project] +VersionControlSupport=kdevgit diff --git a/vSLAM/ch9 project/0.2/0.2.kdev4 b/vSLAM/ch9 project/0.2/0.2.kdev4 new file mode 100644 index 00000000..a8fb52a3 --- /dev/null +++ b/vSLAM/ch9 project/0.2/0.2.kdev4 @@ -0,0 +1,3 @@ +[Project] +Manager=KDevCMakeManager +Name=0.2 diff --git a/vSLAM/ch9 project/0.2/CMakeLists.txt b/vSLAM/ch9 project/0.2/CMakeLists.txt new file mode 100644 index 00000000..a56ffe5f --- /dev/null +++ b/vSLAM/ch9 project/0.2/CMakeLists.txt @@ -0,0 +1,39 @@ +#版本限制 +cmake_minimum_required( VERSION 2.8 ) +#工程名 +project ( myslam ) +#编译器 +set( CMAKE_CXX_COMPILER "g++" ) +#编译模式 +set( CMAKE_BUILD_TYPE "Release" ) +# 添加c++ 11标准支持 +set( CMAKE_CXX_FLAGS "-std=c++11 -march=native -O3" ) + +list( APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules ) +set( EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin ) +set( LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib ) + +############### dependencies ###################### +# Eigen +include_directories( "/usr/include/eigen3" ) +# OpenCV +find_package( OpenCV 3.1 REQUIRED ) +include_directories( ${OpenCV_INCLUDE_DIRS} ) +# Sophus +find_package( Sophus REQUIRED ) +include_directories( ${Sophus_INCLUDE_DIRS} ) +# G2O +find_package( G2O REQUIRED ) +include_directories( ${G2O_INCLUDE_DIRS} ) + +set( THIRD_PARTY_LIBS + ${OpenCV_LIBS} + ${Sophus_LIBRARIES} + g2o_core g2o_stuff g2o_types_sba +) +############### source and test ###################### +include_directories( ${PROJECT_SOURCE_DIR}/include ) +add_subdirectory( src ) +add_subdirectory( test ) + + diff --git a/vSLAM/ch9 project/0.2/bin/run_vo b/vSLAM/ch9 project/0.2/bin/run_vo new file mode 100755 index 00000000..f53c3d7c Binary files /dev/null and b/vSLAM/ch9 project/0.2/bin/run_vo differ diff --git a/vSLAM/ch9 project/0.2/build/CMakeCache.txt b/vSLAM/ch9 project/0.2/build/CMakeCache.txt new file mode 100644 index 00000000..2005a35e --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/CMakeCache.txt @@ -0,0 +1,455 @@ +# This is the CMakeCache file. +# For build in directory: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build +# It was generated by CMake: /usr/bin/cmake +# You can edit this file to change values found and used by cmake. +# If you do not want to change any of the values, simply exit the editor. +# If you do want to change a value, simply edit, save, and exit the editor. +# The syntax for the file is as follows: +# KEY:TYPE=VALUE +# KEY is the name of a variable in the cache. +# TYPE is a hint to GUIs for the type of VALUE, DO NOT EDIT TYPE!. +# VALUE is the current value for the KEY. + +######################## +# EXTERNAL cache entries +######################## + +//Path to a program. +CMAKE_AR:FILEPATH=/usr/bin/ar + +//Choose the type of build, options are: None(CMAKE_CXX_FLAGS or +// CMAKE_C_FLAGS used) Debug Release RelWithDebInfo MinSizeRel. +CMAKE_BUILD_TYPE:STRING=Debug + +//Enable/Disable color output during build. +CMAKE_COLOR_MAKEFILE:BOOL=ON + +//CXX compiler. +CMAKE_CXX_COMPILER:FILEPATH=/usr/bin/c++ + +//Flags used by the compiler during all build types. +CMAKE_CXX_FLAGS:STRING= + +//Flags used by the compiler during debug builds. +CMAKE_CXX_FLAGS_DEBUG:STRING=-g + +//Flags used by the compiler during release minsize builds. +CMAKE_CXX_FLAGS_MINSIZEREL:STRING=-Os -DNDEBUG + +//Flags used by the compiler during release builds (/MD /Ob1 /Oi +// /Ot /Oy /Gs will produce slightly less optimized but smaller +// files). +CMAKE_CXX_FLAGS_RELEASE:STRING=-O3 -DNDEBUG + +//Flags used by the compiler during Release with Debug Info builds. +CMAKE_CXX_FLAGS_RELWITHDEBINFO:STRING=-O2 -g -DNDEBUG + +//C compiler. +CMAKE_C_COMPILER:FILEPATH=/usr/bin/cc + +//Flags used by the compiler during all build types. +CMAKE_C_FLAGS:STRING= + +//Flags used by the compiler during debug builds. +CMAKE_C_FLAGS_DEBUG:STRING=-g + +//Flags used by the compiler during release minsize builds. +CMAKE_C_FLAGS_MINSIZEREL:STRING=-Os -DNDEBUG + +//Flags used by the compiler during release builds (/MD /Ob1 /Oi +// /Ot /Oy /Gs will produce slightly less optimized but smaller +// files). +CMAKE_C_FLAGS_RELEASE:STRING=-O3 -DNDEBUG + +//Flags used by the compiler during Release with Debug Info builds. +CMAKE_C_FLAGS_RELWITHDEBINFO:STRING=-O2 -g -DNDEBUG + +//Flags used by the linker. +CMAKE_EXE_LINKER_FLAGS:STRING=' ' + +//Flags used by the linker during debug builds. +CMAKE_EXE_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during release minsize builds. +CMAKE_EXE_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during release builds. +CMAKE_EXE_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during Release with Debug Info builds. +CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//Enable/Disable output of compile commands during generation. +CMAKE_EXPORT_COMPILE_COMMANDS:BOOL=OFF + +//Install path prefix, prepended onto install directories. +CMAKE_INSTALL_PREFIX:PATH=/usr/local + +//Path to a program. +CMAKE_LINKER:FILEPATH=/usr/bin/ld + +//Path to a program. +CMAKE_MAKE_PROGRAM:FILEPATH=/usr/bin/make + +//Flags used by the linker during the creation of modules. +CMAKE_MODULE_LINKER_FLAGS:STRING=' ' + +//Flags used by the linker during debug builds. +CMAKE_MODULE_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during release minsize builds. +CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during release builds. +CMAKE_MODULE_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during Release with Debug Info builds. +CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//Path to a program. +CMAKE_NM:FILEPATH=/usr/bin/nm + +//Path to a program. +CMAKE_OBJCOPY:FILEPATH=/usr/bin/objcopy + +//Path to a program. +CMAKE_OBJDUMP:FILEPATH=/usr/bin/objdump + +//Value Computed by CMake +CMAKE_PROJECT_NAME:STATIC=myslam + +//Path to a program. +CMAKE_RANLIB:FILEPATH=/usr/bin/ranlib + +//Flags used by the linker during the creation of dll's. +CMAKE_SHARED_LINKER_FLAGS:STRING=' ' + +//Flags used by the linker during debug builds. +CMAKE_SHARED_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during release minsize builds. +CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during release builds. +CMAKE_SHARED_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during Release with Debug Info builds. +CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//If set, runtime paths are not added when installing shared libraries, +// but are added when building. +CMAKE_SKIP_INSTALL_RPATH:BOOL=NO + +//If set, runtime paths are not added when using shared libraries. +CMAKE_SKIP_RPATH:BOOL=NO + +//Flags used by the linker during the creation of static libraries. +CMAKE_STATIC_LINKER_FLAGS:STRING= + +//Flags used by the linker during debug builds. +CMAKE_STATIC_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during release minsize builds. +CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during release builds. +CMAKE_STATIC_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during Release with Debug Info builds. +CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//Path to a program. +CMAKE_STRIP:FILEPATH=/usr/bin/strip + +//If true, cmake will use relative paths in makefiles and projects. +CMAKE_USE_RELATIVE_PATHS:BOOL=OFF + +//If this value is on, makefiles will be generated without the +// .SILENT directive, and all commands will be echoed to the console +// during the make. This is useful for debugging only. With Visual +// Studio IDE projects all commands are done without /nologo. +CMAKE_VERBOSE_MAKEFILE:BOOL=FALSE + +//Path to a library. +G2O_CLI_LIBRARY:FILEPATH=/usr/local/lib/libg2o_cli.so + +//Path to a library. +G2O_CLI_LIBRARY_DEBUG:FILEPATH=G2O_CLI_LIBRARY_DEBUG-NOTFOUND + +//Path to a library. +G2O_CORE_LIBRARY:FILEPATH=/usr/local/lib/libg2o_core.so + +//Path to a library. +G2O_CORE_LIBRARY_DEBUG:FILEPATH=G2O_CORE_LIBRARY_DEBUG-NOTFOUND + +//Path to a file. +G2O_INCLUDE_DIR:PATH=/usr/local/include + +//Path to a library. +G2O_SOLVER_CHOLMOD:FILEPATH=/usr/local/lib/libg2o_solver_cholmod.so + +//Path to a library. +G2O_SOLVER_CHOLMOD_DEBUG:FILEPATH=G2O_SOLVER_CHOLMOD_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_CSPARSE:FILEPATH=/usr/local/lib/libg2o_solver_csparse.so + +//Path to a library. +G2O_SOLVER_CSPARSE_DEBUG:FILEPATH=G2O_SOLVER_CSPARSE_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_CSPARSE_EXTENSION:FILEPATH=/usr/local/lib/libg2o_csparse_extension.so + +//Path to a library. +G2O_SOLVER_CSPARSE_EXTENSION_DEBUG:FILEPATH=G2O_SOLVER_CSPARSE_EXTENSION_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_DENSE:FILEPATH=/usr/local/lib/libg2o_solver_dense.so + +//Path to a library. +G2O_SOLVER_DENSE_DEBUG:FILEPATH=G2O_SOLVER_DENSE_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_EIGEN:FILEPATH=/usr/local/lib/libg2o_solver_eigen.so + +//Path to a library. +G2O_SOLVER_EIGEN_DEBUG:FILEPATH=G2O_SOLVER_EIGEN_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_PCG:FILEPATH=/usr/local/lib/libg2o_solver_pcg.so + +//Path to a library. +G2O_SOLVER_PCG_DEBUG:FILEPATH=G2O_SOLVER_PCG_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_SLAM2D_LINEAR:FILEPATH=/usr/local/lib/libg2o_solver_slam2d_linear.so + +//Path to a library. +G2O_SOLVER_SLAM2D_LINEAR_DEBUG:FILEPATH=G2O_SOLVER_SLAM2D_LINEAR_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_STRUCTURE_ONLY:FILEPATH=/usr/local/lib/libg2o_solver_structure_only.so + +//Path to a library. +G2O_SOLVER_STRUCTURE_ONLY_DEBUG:FILEPATH=G2O_SOLVER_STRUCTURE_ONLY_DEBUG-NOTFOUND + +//Path to a library. +G2O_STUFF_LIBRARY:FILEPATH=/usr/local/lib/libg2o_stuff.so + +//Path to a library. +G2O_STUFF_LIBRARY_DEBUG:FILEPATH=G2O_STUFF_LIBRARY_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_DATA:FILEPATH=/usr/local/lib/libg2o_types_data.so + +//Path to a library. +G2O_TYPES_DATA_DEBUG:FILEPATH=G2O_TYPES_DATA_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_ICP:FILEPATH=/usr/local/lib/libg2o_types_icp.so + +//Path to a library. +G2O_TYPES_ICP_DEBUG:FILEPATH=G2O_TYPES_ICP_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_SBA:FILEPATH=/usr/local/lib/libg2o_types_sba.so + +//Path to a library. +G2O_TYPES_SBA_DEBUG:FILEPATH=G2O_TYPES_SBA_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_SCLAM2D:FILEPATH=/usr/local/lib/libg2o_types_sclam2d.so + +//Path to a library. +G2O_TYPES_SCLAM2D_DEBUG:FILEPATH=G2O_TYPES_SCLAM2D_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_SIM3:FILEPATH=/usr/local/lib/libg2o_types_sim3.so + +//Path to a library. +G2O_TYPES_SIM3_DEBUG:FILEPATH=G2O_TYPES_SIM3_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_SLAM2D:FILEPATH=/usr/local/lib/libg2o_types_slam2d.so + +//Path to a library. +G2O_TYPES_SLAM2D_DEBUG:FILEPATH=G2O_TYPES_SLAM2D_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_SLAM3D:FILEPATH=/usr/local/lib/libg2o_types_slam3d.so + +//Path to a library. +G2O_TYPES_SLAM3D_DEBUG:FILEPATH=G2O_TYPES_SLAM3D_DEBUG-NOTFOUND + +//Path where debug 3rdparty OpenCV dependencies are located +OpenCV_3RDPARTY_LIB_DIR_DBG:PATH=/usr/local/share/OpenCV/3rdparty/lib + +//Path where release 3rdparty OpenCV dependencies are located +OpenCV_3RDPARTY_LIB_DIR_OPT:PATH=/usr/local/share/OpenCV/3rdparty/lib + +OpenCV_CONFIG_PATH:FILEPATH=/usr/local/share/OpenCV + +//The directory containing a CMake configuration file for OpenCV. +OpenCV_DIR:PATH=/usr/local/share/OpenCV + +//Path where debug OpenCV libraries are located +OpenCV_LIB_DIR_DBG:PATH= + +//Path where release OpenCV libraries are located +OpenCV_LIB_DIR_OPT:PATH= + +//The directory containing a CMake configuration file for Sophus. +Sophus_DIR:PATH=/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build + +//Value Computed by CMake +myslam_BINARY_DIR:STATIC=/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build + +//Dependencies for the target +myslam_LIB_DEPENDS:STATIC=general;opencv_viz;general;opencv_videostab;general;opencv_videoio;general;opencv_video;general;opencv_superres;general;opencv_stitching;general;opencv_shape;general;opencv_photo;general;opencv_objdetect;general;opencv_ml;general;opencv_imgproc;general;opencv_imgcodecs;general;opencv_highgui;general;opencv_flann;general;opencv_features2d;general;opencv_core;general;opencv_calib3d;general;/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build/libSophus.so;general;g2o_core;general;g2o_stuff;general;g2o_types_sba; + +//Value Computed by CMake +myslam_SOURCE_DIR:STATIC=/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2 + + +######################## +# INTERNAL cache entries +######################## + +//ADVANCED property for variable: CMAKE_AR +CMAKE_AR-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_BUILD_TOOL +CMAKE_BUILD_TOOL-ADVANCED:INTERNAL=1 +//What is the target build tool cmake is generating for. +CMAKE_BUILD_TOOL:INTERNAL=/usr/bin/make +//This is the directory where this CMakeCache.txt was created +CMAKE_CACHEFILE_DIR:INTERNAL=/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build +//Major version of cmake used to create the current loaded cache +CMAKE_CACHE_MAJOR_VERSION:INTERNAL=2 +//Minor version of cmake used to create the current loaded cache +CMAKE_CACHE_MINOR_VERSION:INTERNAL=8 +//Patch version of cmake used to create the current loaded cache +CMAKE_CACHE_PATCH_VERSION:INTERNAL=12 +//ADVANCED property for variable: CMAKE_COLOR_MAKEFILE +CMAKE_COLOR_MAKEFILE-ADVANCED:INTERNAL=1 +//Path to CMake executable. +CMAKE_COMMAND:INTERNAL=/usr/bin/cmake +//Path to cpack program executable. +CMAKE_CPACK_COMMAND:INTERNAL=/usr/bin/cpack +//Path to ctest program executable. +CMAKE_CTEST_COMMAND:INTERNAL=/usr/bin/ctest +//ADVANCED property for variable: CMAKE_CXX_COMPILER +CMAKE_CXX_COMPILER-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS +CMAKE_CXX_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_DEBUG +CMAKE_CXX_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_MINSIZEREL +CMAKE_CXX_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_RELEASE +CMAKE_CXX_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_RELWITHDEBINFO +CMAKE_CXX_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_COMPILER +CMAKE_C_COMPILER-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS +CMAKE_C_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS_DEBUG +CMAKE_C_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS_MINSIZEREL +CMAKE_C_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS_RELEASE +CMAKE_C_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS_RELWITHDEBINFO +CMAKE_C_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//Executable file format +CMAKE_EXECUTABLE_FORMAT:INTERNAL=ELF +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS +CMAKE_EXE_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_DEBUG +CMAKE_EXE_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_MINSIZEREL +CMAKE_EXE_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_RELEASE +CMAKE_EXE_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXPORT_COMPILE_COMMANDS +CMAKE_EXPORT_COMPILE_COMMANDS-ADVANCED:INTERNAL=1 +//Name of generator. +CMAKE_GENERATOR:INTERNAL=Unix Makefiles +//Name of generator toolset. +CMAKE_GENERATOR_TOOLSET:INTERNAL= +//Start directory with the top level CMakeLists.txt file for this +// project +CMAKE_HOME_DIRECTORY:INTERNAL=/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2 +//Install .so files without execute permission. +CMAKE_INSTALL_SO_NO_EXE:INTERNAL=1 +//ADVANCED property for variable: CMAKE_LINKER +CMAKE_LINKER-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MAKE_PROGRAM +CMAKE_MAKE_PROGRAM-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS +CMAKE_MODULE_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_DEBUG +CMAKE_MODULE_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL +CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_RELEASE +CMAKE_MODULE_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_NM +CMAKE_NM-ADVANCED:INTERNAL=1 +//number of local generators +CMAKE_NUMBER_OF_LOCAL_GENERATORS:INTERNAL=3 +//ADVANCED property for variable: CMAKE_OBJCOPY +CMAKE_OBJCOPY-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_OBJDUMP +CMAKE_OBJDUMP-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_RANLIB +CMAKE_RANLIB-ADVANCED:INTERNAL=1 +//Path to CMake installation. +CMAKE_ROOT:INTERNAL=/usr/share/cmake-2.8 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS +CMAKE_SHARED_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_DEBUG +CMAKE_SHARED_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL +CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_RELEASE +CMAKE_SHARED_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SKIP_INSTALL_RPATH +CMAKE_SKIP_INSTALL_RPATH-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SKIP_RPATH +CMAKE_SKIP_RPATH-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS +CMAKE_STATIC_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_DEBUG +CMAKE_STATIC_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL +CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_RELEASE +CMAKE_STATIC_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STRIP +CMAKE_STRIP-ADVANCED:INTERNAL=1 +//uname command +CMAKE_UNAME:INTERNAL=/bin/uname +//ADVANCED property for variable: CMAKE_USE_RELATIVE_PATHS +CMAKE_USE_RELATIVE_PATHS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_VERBOSE_MAKEFILE +CMAKE_VERBOSE_MAKEFILE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: OpenCV_3RDPARTY_LIB_DIR_DBG +OpenCV_3RDPARTY_LIB_DIR_DBG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: OpenCV_3RDPARTY_LIB_DIR_OPT +OpenCV_3RDPARTY_LIB_DIR_OPT-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: OpenCV_CONFIG_PATH +OpenCV_CONFIG_PATH-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: OpenCV_LIB_DIR_DBG +OpenCV_LIB_DIR_DBG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: OpenCV_LIB_DIR_OPT +OpenCV_LIB_DIR_OPT-ADVANCED:INTERNAL=1 + diff --git a/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CMakeCCompiler.cmake b/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CMakeCCompiler.cmake new file mode 100644 index 00000000..f4a508be --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CMakeCCompiler.cmake @@ -0,0 +1,56 @@ +set(CMAKE_C_COMPILER "/usr/bin/cc") +set(CMAKE_C_COMPILER_ARG1 "") +set(CMAKE_C_COMPILER_ID "GNU") +set(CMAKE_C_COMPILER_VERSION "4.8.4") +set(CMAKE_C_PLATFORM_ID "Linux") + +set(CMAKE_AR "/usr/bin/ar") +set(CMAKE_RANLIB "/usr/bin/ranlib") +set(CMAKE_LINKER "/usr/bin/ld") +set(CMAKE_COMPILER_IS_GNUCC 1) +set(CMAKE_C_COMPILER_LOADED 1) +set(CMAKE_C_COMPILER_WORKS TRUE) +set(CMAKE_C_ABI_COMPILED TRUE) +set(CMAKE_COMPILER_IS_MINGW ) +set(CMAKE_COMPILER_IS_CYGWIN ) +if(CMAKE_COMPILER_IS_CYGWIN) + set(CYGWIN 1) + set(UNIX 1) +endif() + +set(CMAKE_C_COMPILER_ENV_VAR "CC") + +if(CMAKE_COMPILER_IS_MINGW) + set(MINGW 1) +endif() +set(CMAKE_C_COMPILER_ID_RUN 1) +set(CMAKE_C_SOURCE_FILE_EXTENSIONS c) +set(CMAKE_C_IGNORE_EXTENSIONS h;H;o;O;obj;OBJ;def;DEF;rc;RC) +set(CMAKE_C_LINKER_PREFERENCE 10) + +# Save compiler ABI information. +set(CMAKE_C_SIZEOF_DATA_PTR "8") +set(CMAKE_C_COMPILER_ABI "ELF") +set(CMAKE_C_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") + +if(CMAKE_C_SIZEOF_DATA_PTR) + set(CMAKE_SIZEOF_VOID_P "${CMAKE_C_SIZEOF_DATA_PTR}") +endif() + +if(CMAKE_C_COMPILER_ABI) + set(CMAKE_INTERNAL_PLATFORM_ABI "${CMAKE_C_COMPILER_ABI}") +endif() + +if(CMAKE_C_LIBRARY_ARCHITECTURE) + set(CMAKE_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") +endif() + + + + +set(CMAKE_C_IMPLICIT_LINK_LIBRARIES "c") +set(CMAKE_C_IMPLICIT_LINK_DIRECTORIES "/usr/lib/gcc/x86_64-linux-gnu/4.8;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib") +set(CMAKE_C_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES "") + + + diff --git a/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake b/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake new file mode 100644 index 00000000..1ca40dbc --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake @@ -0,0 +1,57 @@ +set(CMAKE_CXX_COMPILER "/usr/bin/c++") +set(CMAKE_CXX_COMPILER_ARG1 "") +set(CMAKE_CXX_COMPILER_ID "GNU") +set(CMAKE_CXX_COMPILER_VERSION "4.8.4") +set(CMAKE_CXX_PLATFORM_ID "Linux") + +set(CMAKE_AR "/usr/bin/ar") +set(CMAKE_RANLIB "/usr/bin/ranlib") +set(CMAKE_LINKER "/usr/bin/ld") +set(CMAKE_COMPILER_IS_GNUCXX 1) +set(CMAKE_CXX_COMPILER_LOADED 1) +set(CMAKE_CXX_COMPILER_WORKS TRUE) +set(CMAKE_CXX_ABI_COMPILED TRUE) +set(CMAKE_COMPILER_IS_MINGW ) +set(CMAKE_COMPILER_IS_CYGWIN ) +if(CMAKE_COMPILER_IS_CYGWIN) + set(CYGWIN 1) + set(UNIX 1) +endif() + +set(CMAKE_CXX_COMPILER_ENV_VAR "CXX") + +if(CMAKE_COMPILER_IS_MINGW) + set(MINGW 1) +endif() +set(CMAKE_CXX_COMPILER_ID_RUN 1) +set(CMAKE_CXX_IGNORE_EXTENSIONS inl;h;hpp;HPP;H;o;O;obj;OBJ;def;DEF;rc;RC) +set(CMAKE_CXX_SOURCE_FILE_EXTENSIONS C;M;c++;cc;cpp;cxx;m;mm;CPP) +set(CMAKE_CXX_LINKER_PREFERENCE 30) +set(CMAKE_CXX_LINKER_PREFERENCE_PROPAGATES 1) + +# Save compiler ABI information. +set(CMAKE_CXX_SIZEOF_DATA_PTR "8") +set(CMAKE_CXX_COMPILER_ABI "ELF") +set(CMAKE_CXX_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") + +if(CMAKE_CXX_SIZEOF_DATA_PTR) + set(CMAKE_SIZEOF_VOID_P "${CMAKE_CXX_SIZEOF_DATA_PTR}") +endif() + +if(CMAKE_CXX_COMPILER_ABI) + set(CMAKE_INTERNAL_PLATFORM_ABI "${CMAKE_CXX_COMPILER_ABI}") +endif() + +if(CMAKE_CXX_LIBRARY_ARCHITECTURE) + set(CMAKE_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") +endif() + + + + +set(CMAKE_CXX_IMPLICIT_LINK_LIBRARIES "stdc++;m;c") +set(CMAKE_CXX_IMPLICIT_LINK_DIRECTORIES "/usr/lib/gcc/x86_64-linux-gnu/4.8;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib") +set(CMAKE_CXX_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES "") + + + diff --git a/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_C.bin b/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_C.bin new file mode 100755 index 00000000..f909aaac Binary files /dev/null and b/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_C.bin differ diff --git a/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_CXX.bin b/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_CXX.bin new file mode 100755 index 00000000..d6b41c89 Binary files /dev/null and b/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_CXX.bin differ diff --git a/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CMakeSystem.cmake b/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CMakeSystem.cmake new file mode 100644 index 00000000..8444407c --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CMakeSystem.cmake @@ -0,0 +1,15 @@ +set(CMAKE_HOST_SYSTEM "Linux-4.4.0-94-generic") +set(CMAKE_HOST_SYSTEM_NAME "Linux") +set(CMAKE_HOST_SYSTEM_VERSION "4.4.0-94-generic") +set(CMAKE_HOST_SYSTEM_PROCESSOR "x86_64") + + + +set(CMAKE_SYSTEM "Linux-4.4.0-94-generic") +set(CMAKE_SYSTEM_NAME "Linux") +set(CMAKE_SYSTEM_VERSION "4.4.0-94-generic") +set(CMAKE_SYSTEM_PROCESSOR "x86_64") + +set(CMAKE_CROSSCOMPILING "FALSE") + +set(CMAKE_SYSTEM_LOADED 1) diff --git a/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CompilerIdC/CMakeCCompilerId.c b/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CompilerIdC/CMakeCCompilerId.c new file mode 100644 index 00000000..cba81d4a --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CompilerIdC/CMakeCCompilerId.c @@ -0,0 +1,389 @@ +#ifdef __cplusplus +# error "A C++ compiler has been selected for C." +#endif + +/* Version number components: V=Version, R=Revision, P=Patch + Version date components: YYYY=Year, MM=Month, DD=Day */ + +#if defined(__18CXX) +# define ID_VOID_MAIN +#endif + +#if defined(__INTEL_COMPILER) || defined(__ICC) +# define COMPILER_ID "Intel" + /* __INTEL_COMPILER = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER/100) +# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER % 10) +# if defined(__INTEL_COMPILER_BUILD_DATE) + /* __INTEL_COMPILER_BUILD_DATE = YYYYMMDD */ +# define COMPILER_VERSION_TWEAK DEC(__INTEL_COMPILER_BUILD_DATE) +# endif + +#elif defined(__PATHCC__) +# define COMPILER_ID "PathScale" +# define COMPILER_VERSION_MAJOR DEC(__PATHCC__) +# define COMPILER_VERSION_MINOR DEC(__PATHCC_MINOR__) +# if defined(__PATHCC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__PATHCC_PATCHLEVEL__) +# endif + +#elif defined(__clang__) +# define COMPILER_ID "Clang" +# define COMPILER_VERSION_MAJOR DEC(__clang_major__) +# define COMPILER_VERSION_MINOR DEC(__clang_minor__) +# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__) + +#elif defined(__BORLANDC__) && defined(__CODEGEARC_VERSION__) +# define COMPILER_ID "Embarcadero" +# define COMPILER_VERSION_MAJOR HEX(__CODEGEARC_VERSION__>>24 & 0x00FF) +# define COMPILER_VERSION_MINOR HEX(__CODEGEARC_VERSION__>>16 & 0x00FF) +# define COMPILER_VERSION_PATCH HEX(__CODEGEARC_VERSION__ & 0xFFFF) + +#elif defined(__BORLANDC__) +# define COMPILER_ID "Borland" + /* __BORLANDC__ = 0xVRR */ +# define COMPILER_VERSION_MAJOR HEX(__BORLANDC__>>8) +# define COMPILER_VERSION_MINOR HEX(__BORLANDC__ & 0xFF) + +#elif defined(__WATCOMC__) +# define COMPILER_ID "Watcom" + /* __WATCOMC__ = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(__WATCOMC__ / 100) +# define COMPILER_VERSION_MINOR DEC(__WATCOMC__ % 100) + +#elif defined(__SUNPRO_C) +# define COMPILER_ID "SunPro" +# if __SUNPRO_C >= 0x5100 + /* __SUNPRO_C = 0xVRRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_C>>12) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_C>>4 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_C & 0xF) +# else + /* __SUNPRO_C = 0xVRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_C>>8) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_C>>4 & 0xF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_C & 0xF) +# endif + +#elif defined(__HP_cc) +# define COMPILER_ID "HP" + /* __HP_cc = VVRRPP */ +# define COMPILER_VERSION_MAJOR DEC(__HP_cc/10000) +# define COMPILER_VERSION_MINOR DEC(__HP_cc/100 % 100) +# define COMPILER_VERSION_PATCH DEC(__HP_cc % 100) + +#elif defined(__DECC) +# define COMPILER_ID "Compaq" + /* __DECC_VER = VVRRTPPPP */ +# define COMPILER_VERSION_MAJOR DEC(__DECC_VER/10000000) +# define COMPILER_VERSION_MINOR DEC(__DECC_VER/100000 % 100) +# define COMPILER_VERSION_PATCH DEC(__DECC_VER % 10000) + +#elif defined(__IBMC__) +# if defined(__COMPILER_VER__) +# define COMPILER_ID "zOS" +# else +# if __IBMC__ >= 800 +# define COMPILER_ID "XL" +# else +# define COMPILER_ID "VisualAge" +# endif + /* __IBMC__ = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__IBMC__/100) +# define COMPILER_VERSION_MINOR DEC(__IBMC__/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__IBMC__ % 10) +# endif + +#elif defined(__PGI) +# define COMPILER_ID "PGI" +# define COMPILER_VERSION_MAJOR DEC(__PGIC__) +# define COMPILER_VERSION_MINOR DEC(__PGIC_MINOR__) +# if defined(__PGIC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__PGIC_PATCHLEVEL__) +# endif + +#elif defined(_CRAYC) +# define COMPILER_ID "Cray" +# define COMPILER_VERSION_MAJOR DEC(_RELEASE) +# define COMPILER_VERSION_MINOR DEC(_RELEASE_MINOR) + +#elif defined(__TI_COMPILER_VERSION__) +# define COMPILER_ID "TI" + /* __TI_COMPILER_VERSION__ = VVVRRRPPP */ +# define COMPILER_VERSION_MAJOR DEC(__TI_COMPILER_VERSION__/1000000) +# define COMPILER_VERSION_MINOR DEC(__TI_COMPILER_VERSION__/1000 % 1000) +# define COMPILER_VERSION_PATCH DEC(__TI_COMPILER_VERSION__ % 1000) + +#elif defined(__TINYC__) +# define COMPILER_ID "TinyCC" + +#elif defined(__SCO_VERSION__) +# define COMPILER_ID "SCO" + +#elif defined(__GNUC__) +# define COMPILER_ID "GNU" +# define COMPILER_VERSION_MAJOR DEC(__GNUC__) +# define COMPILER_VERSION_MINOR DEC(__GNUC_MINOR__) +# if defined(__GNUC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__) +# endif + +#elif defined(_MSC_VER) +# define COMPILER_ID "MSVC" + /* _MSC_VER = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(_MSC_VER / 100) +# define COMPILER_VERSION_MINOR DEC(_MSC_VER % 100) +# if defined(_MSC_FULL_VER) +# if _MSC_VER >= 1400 + /* _MSC_FULL_VER = VVRRPPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 100000) +# else + /* _MSC_FULL_VER = VVRRPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 10000) +# endif +# endif +# if defined(_MSC_BUILD) +# define COMPILER_VERSION_TWEAK DEC(_MSC_BUILD) +# endif + +/* Analog VisualDSP++ >= 4.5.6 */ +#elif defined(__VISUALDSPVERSION__) +# define COMPILER_ID "ADSP" + /* __VISUALDSPVERSION__ = 0xVVRRPP00 */ +# define COMPILER_VERSION_MAJOR HEX(__VISUALDSPVERSION__>>24) +# define COMPILER_VERSION_MINOR HEX(__VISUALDSPVERSION__>>16 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__VISUALDSPVERSION__>>8 & 0xFF) + +/* Analog VisualDSP++ < 4.5.6 */ +#elif defined(__ADSPBLACKFIN__) || defined(__ADSPTS__) || defined(__ADSP21000__) +# define COMPILER_ID "ADSP" + +/* IAR Systems compiler for embedded systems. + http://www.iar.com */ +#elif defined(__IAR_SYSTEMS_ICC__ ) || defined(__IAR_SYSTEMS_ICC) +# define COMPILER_ID "IAR" + +/* sdcc, the small devices C compiler for embedded systems, + http://sdcc.sourceforge.net */ +#elif defined(SDCC) +# define COMPILER_ID "SDCC" + /* SDCC = VRP */ +# define COMPILER_VERSION_MAJOR DEC(SDCC/100) +# define COMPILER_VERSION_MINOR DEC(SDCC/10 % 10) +# define COMPILER_VERSION_PATCH DEC(SDCC % 10) + +#elif defined(_SGI_COMPILER_VERSION) || defined(_COMPILER_VERSION) +# define COMPILER_ID "MIPSpro" +# if defined(_SGI_COMPILER_VERSION) + /* _SGI_COMPILER_VERSION = VRP */ +# define COMPILER_VERSION_MAJOR DEC(_SGI_COMPILER_VERSION/100) +# define COMPILER_VERSION_MINOR DEC(_SGI_COMPILER_VERSION/10 % 10) +# define COMPILER_VERSION_PATCH DEC(_SGI_COMPILER_VERSION % 10) +# else + /* _COMPILER_VERSION = VRP */ +# define COMPILER_VERSION_MAJOR DEC(_COMPILER_VERSION/100) +# define COMPILER_VERSION_MINOR DEC(_COMPILER_VERSION/10 % 10) +# define COMPILER_VERSION_PATCH DEC(_COMPILER_VERSION % 10) +# endif + +/* This compiler is either not known or is too old to define an + identification macro. Try to identify the platform and guess that + it is the native compiler. */ +#elif defined(__sgi) +# define COMPILER_ID "MIPSpro" + +#elif defined(__hpux) || defined(__hpua) +# define COMPILER_ID "HP" + +#else /* unknown compiler */ +# define COMPILER_ID "" + +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_compiler = "INFO" ":" "compiler[" COMPILER_ID "]"; + +/* Identify known platforms by name. */ +#if defined(__linux) || defined(__linux__) || defined(linux) +# define PLATFORM_ID "Linux" + +#elif defined(__CYGWIN__) +# define PLATFORM_ID "Cygwin" + +#elif defined(__MINGW32__) +# define PLATFORM_ID "MinGW" + +#elif defined(__APPLE__) +# define PLATFORM_ID "Darwin" + +#elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32) +# define PLATFORM_ID "Windows" + +#elif defined(__FreeBSD__) || defined(__FreeBSD) +# define PLATFORM_ID "FreeBSD" + +#elif defined(__NetBSD__) || defined(__NetBSD) +# define PLATFORM_ID "NetBSD" + +#elif defined(__OpenBSD__) || defined(__OPENBSD) +# define PLATFORM_ID "OpenBSD" + +#elif defined(__sun) || defined(sun) +# define PLATFORM_ID "SunOS" + +#elif defined(_AIX) || defined(__AIX) || defined(__AIX__) || defined(__aix) || defined(__aix__) +# define PLATFORM_ID "AIX" + +#elif defined(__sgi) || defined(__sgi__) || defined(_SGI) +# define PLATFORM_ID "IRIX" + +#elif defined(__hpux) || defined(__hpux__) +# define PLATFORM_ID "HP-UX" + +#elif defined(__HAIKU__) +# define PLATFORM_ID "Haiku" + +#elif defined(__BeOS) || defined(__BEOS__) || defined(_BEOS) +# define PLATFORM_ID "BeOS" + +#elif defined(__QNX__) || defined(__QNXNTO__) +# define PLATFORM_ID "QNX" + +#elif defined(__tru64) || defined(_tru64) || defined(__TRU64__) +# define PLATFORM_ID "Tru64" + +#elif defined(__riscos) || defined(__riscos__) +# define PLATFORM_ID "RISCos" + +#elif defined(__sinix) || defined(__sinix__) || defined(__SINIX__) +# define PLATFORM_ID "SINIX" + +#elif defined(__UNIX_SV__) +# define PLATFORM_ID "UNIX_SV" + +#elif defined(__bsdos__) +# define PLATFORM_ID "BSDOS" + +#elif defined(_MPRAS) || defined(MPRAS) +# define PLATFORM_ID "MP-RAS" + +#elif defined(__osf) || defined(__osf__) +# define PLATFORM_ID "OSF1" + +#elif defined(_SCO_SV) || defined(SCO_SV) || defined(sco_sv) +# define PLATFORM_ID "SCO_SV" + +#elif defined(__ultrix) || defined(__ultrix__) || defined(_ULTRIX) +# define PLATFORM_ID "ULTRIX" + +#elif defined(__XENIX__) || defined(_XENIX) || defined(XENIX) +# define PLATFORM_ID "Xenix" + +#else /* unknown platform */ +# define PLATFORM_ID "" + +#endif + +/* For windows compilers MSVC and Intel we can determine + the architecture of the compiler being used. This is because + the compilers do not have flags that can change the architecture, + but rather depend on which compiler is being used +*/ +#if defined(_WIN32) && defined(_MSC_VER) +# if defined(_M_IA64) +# define ARCHITECTURE_ID "IA64" + +# elif defined(_M_X64) || defined(_M_AMD64) +# define ARCHITECTURE_ID "x64" + +# elif defined(_M_IX86) +# define ARCHITECTURE_ID "X86" + +# elif defined(_M_ARM) +# define ARCHITECTURE_ID "ARM" + +# elif defined(_M_MIPS) +# define ARCHITECTURE_ID "MIPS" + +# elif defined(_M_SH) +# define ARCHITECTURE_ID "SHx" + +# else /* unknown architecture */ +# define ARCHITECTURE_ID "" +# endif + +#else +# define ARCHITECTURE_ID "" +#endif + +/* Convert integer to decimal digit literals. */ +#define DEC(n) \ + ('0' + (((n) / 10000000)%10)), \ + ('0' + (((n) / 1000000)%10)), \ + ('0' + (((n) / 100000)%10)), \ + ('0' + (((n) / 10000)%10)), \ + ('0' + (((n) / 1000)%10)), \ + ('0' + (((n) / 100)%10)), \ + ('0' + (((n) / 10)%10)), \ + ('0' + ((n) % 10)) + +/* Convert integer to hex digit literals. */ +#define HEX(n) \ + ('0' + ((n)>>28 & 0xF)), \ + ('0' + ((n)>>24 & 0xF)), \ + ('0' + ((n)>>20 & 0xF)), \ + ('0' + ((n)>>16 & 0xF)), \ + ('0' + ((n)>>12 & 0xF)), \ + ('0' + ((n)>>8 & 0xF)), \ + ('0' + ((n)>>4 & 0xF)), \ + ('0' + ((n) & 0xF)) + +/* Construct a string literal encoding the version number components. */ +#ifdef COMPILER_VERSION_MAJOR +char const info_version[] = { + 'I', 'N', 'F', 'O', ':', + 'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','[', + COMPILER_VERSION_MAJOR, +# ifdef COMPILER_VERSION_MINOR + '.', COMPILER_VERSION_MINOR, +# ifdef COMPILER_VERSION_PATCH + '.', COMPILER_VERSION_PATCH, +# ifdef COMPILER_VERSION_TWEAK + '.', COMPILER_VERSION_TWEAK, +# endif +# endif +# endif + ']','\0'}; +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_platform = "INFO" ":" "platform[" PLATFORM_ID "]"; +char const* info_arch = "INFO" ":" "arch[" ARCHITECTURE_ID "]"; + + + +/*--------------------------------------------------------------------------*/ + +#ifdef ID_VOID_MAIN +void main() {} +#else +int main(int argc, char* argv[]) +{ + int require = 0; + require += info_compiler[argc]; + require += info_platform[argc]; + require += info_arch[argc]; +#ifdef COMPILER_VERSION_MAJOR + require += info_version[argc]; +#endif + (void)argv; + return require; +} +#endif diff --git a/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CompilerIdC/a.out b/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CompilerIdC/a.out new file mode 100755 index 00000000..49a5ca2e Binary files /dev/null and b/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CompilerIdC/a.out differ diff --git a/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CompilerIdCXX/CMakeCXXCompilerId.cpp b/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CompilerIdCXX/CMakeCXXCompilerId.cpp new file mode 100644 index 00000000..e8220b26 --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CompilerIdCXX/CMakeCXXCompilerId.cpp @@ -0,0 +1,377 @@ +/* This source file must have a .cpp extension so that all C++ compilers + recognize the extension without flags. Borland does not know .cxx for + example. */ +#ifndef __cplusplus +# error "A C compiler has been selected for C++." +#endif + +/* Version number components: V=Version, R=Revision, P=Patch + Version date components: YYYY=Year, MM=Month, DD=Day */ + +#if defined(__COMO__) +# define COMPILER_ID "Comeau" + /* __COMO_VERSION__ = VRR */ +# define COMPILER_VERSION_MAJOR DEC(__COMO_VERSION__ / 100) +# define COMPILER_VERSION_MINOR DEC(__COMO_VERSION__ % 100) + +#elif defined(__INTEL_COMPILER) || defined(__ICC) +# define COMPILER_ID "Intel" + /* __INTEL_COMPILER = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER/100) +# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER % 10) +# if defined(__INTEL_COMPILER_BUILD_DATE) + /* __INTEL_COMPILER_BUILD_DATE = YYYYMMDD */ +# define COMPILER_VERSION_TWEAK DEC(__INTEL_COMPILER_BUILD_DATE) +# endif + +#elif defined(__PATHCC__) +# define COMPILER_ID "PathScale" +# define COMPILER_VERSION_MAJOR DEC(__PATHCC__) +# define COMPILER_VERSION_MINOR DEC(__PATHCC_MINOR__) +# if defined(__PATHCC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__PATHCC_PATCHLEVEL__) +# endif + +#elif defined(__clang__) +# define COMPILER_ID "Clang" +# define COMPILER_VERSION_MAJOR DEC(__clang_major__) +# define COMPILER_VERSION_MINOR DEC(__clang_minor__) +# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__) + +#elif defined(__BORLANDC__) && defined(__CODEGEARC_VERSION__) +# define COMPILER_ID "Embarcadero" +# define COMPILER_VERSION_MAJOR HEX(__CODEGEARC_VERSION__>>24 & 0x00FF) +# define COMPILER_VERSION_MINOR HEX(__CODEGEARC_VERSION__>>16 & 0x00FF) +# define COMPILER_VERSION_PATCH HEX(__CODEGEARC_VERSION__ & 0xFFFF) + +#elif defined(__BORLANDC__) +# define COMPILER_ID "Borland" + /* __BORLANDC__ = 0xVRR */ +# define COMPILER_VERSION_MAJOR HEX(__BORLANDC__>>8) +# define COMPILER_VERSION_MINOR HEX(__BORLANDC__ & 0xFF) + +#elif defined(__WATCOMC__) +# define COMPILER_ID "Watcom" + /* __WATCOMC__ = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(__WATCOMC__ / 100) +# define COMPILER_VERSION_MINOR DEC(__WATCOMC__ % 100) + +#elif defined(__SUNPRO_CC) +# define COMPILER_ID "SunPro" +# if __SUNPRO_CC >= 0x5100 + /* __SUNPRO_CC = 0xVRRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_CC>>12) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_CC>>4 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_CC & 0xF) +# else + /* __SUNPRO_CC = 0xVRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_CC>>8) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_CC>>4 & 0xF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_CC & 0xF) +# endif + +#elif defined(__HP_aCC) +# define COMPILER_ID "HP" + /* __HP_aCC = VVRRPP */ +# define COMPILER_VERSION_MAJOR DEC(__HP_aCC/10000) +# define COMPILER_VERSION_MINOR DEC(__HP_aCC/100 % 100) +# define COMPILER_VERSION_PATCH DEC(__HP_aCC % 100) + +#elif defined(__DECCXX) +# define COMPILER_ID "Compaq" + /* __DECCXX_VER = VVRRTPPPP */ +# define COMPILER_VERSION_MAJOR DEC(__DECCXX_VER/10000000) +# define COMPILER_VERSION_MINOR DEC(__DECCXX_VER/100000 % 100) +# define COMPILER_VERSION_PATCH DEC(__DECCXX_VER % 10000) + +#elif defined(__IBMCPP__) +# if defined(__COMPILER_VER__) +# define COMPILER_ID "zOS" +# else +# if __IBMCPP__ >= 800 +# define COMPILER_ID "XL" +# else +# define COMPILER_ID "VisualAge" +# endif + /* __IBMCPP__ = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__IBMCPP__/100) +# define COMPILER_VERSION_MINOR DEC(__IBMCPP__/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__IBMCPP__ % 10) +# endif + +#elif defined(__PGI) +# define COMPILER_ID "PGI" +# define COMPILER_VERSION_MAJOR DEC(__PGIC__) +# define COMPILER_VERSION_MINOR DEC(__PGIC_MINOR__) +# if defined(__PGIC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__PGIC_PATCHLEVEL__) +# endif + +#elif defined(_CRAYC) +# define COMPILER_ID "Cray" +# define COMPILER_VERSION_MAJOR DEC(_RELEASE) +# define COMPILER_VERSION_MINOR DEC(_RELEASE_MINOR) + +#elif defined(__TI_COMPILER_VERSION__) +# define COMPILER_ID "TI" + /* __TI_COMPILER_VERSION__ = VVVRRRPPP */ +# define COMPILER_VERSION_MAJOR DEC(__TI_COMPILER_VERSION__/1000000) +# define COMPILER_VERSION_MINOR DEC(__TI_COMPILER_VERSION__/1000 % 1000) +# define COMPILER_VERSION_PATCH DEC(__TI_COMPILER_VERSION__ % 1000) + +#elif defined(__SCO_VERSION__) +# define COMPILER_ID "SCO" + +#elif defined(__GNUC__) +# define COMPILER_ID "GNU" +# define COMPILER_VERSION_MAJOR DEC(__GNUC__) +# define COMPILER_VERSION_MINOR DEC(__GNUC_MINOR__) +# if defined(__GNUC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__) +# endif + +#elif defined(_MSC_VER) +# define COMPILER_ID "MSVC" + /* _MSC_VER = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(_MSC_VER / 100) +# define COMPILER_VERSION_MINOR DEC(_MSC_VER % 100) +# if defined(_MSC_FULL_VER) +# if _MSC_VER >= 1400 + /* _MSC_FULL_VER = VVRRPPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 100000) +# else + /* _MSC_FULL_VER = VVRRPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 10000) +# endif +# endif +# if defined(_MSC_BUILD) +# define COMPILER_VERSION_TWEAK DEC(_MSC_BUILD) +# endif + +/* Analog VisualDSP++ >= 4.5.6 */ +#elif defined(__VISUALDSPVERSION__) +# define COMPILER_ID "ADSP" + /* __VISUALDSPVERSION__ = 0xVVRRPP00 */ +# define COMPILER_VERSION_MAJOR HEX(__VISUALDSPVERSION__>>24) +# define COMPILER_VERSION_MINOR HEX(__VISUALDSPVERSION__>>16 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__VISUALDSPVERSION__>>8 & 0xFF) + +/* Analog VisualDSP++ < 4.5.6 */ +#elif defined(__ADSPBLACKFIN__) || defined(__ADSPTS__) || defined(__ADSP21000__) +# define COMPILER_ID "ADSP" + +/* IAR Systems compiler for embedded systems. + http://www.iar.com */ +#elif defined(__IAR_SYSTEMS_ICC__ ) || defined(__IAR_SYSTEMS_ICC) +# define COMPILER_ID "IAR" + +#elif defined(_SGI_COMPILER_VERSION) || defined(_COMPILER_VERSION) +# define COMPILER_ID "MIPSpro" +# if defined(_SGI_COMPILER_VERSION) + /* _SGI_COMPILER_VERSION = VRP */ +# define COMPILER_VERSION_MAJOR DEC(_SGI_COMPILER_VERSION/100) +# define COMPILER_VERSION_MINOR DEC(_SGI_COMPILER_VERSION/10 % 10) +# define COMPILER_VERSION_PATCH DEC(_SGI_COMPILER_VERSION % 10) +# else + /* _COMPILER_VERSION = VRP */ +# define COMPILER_VERSION_MAJOR DEC(_COMPILER_VERSION/100) +# define COMPILER_VERSION_MINOR DEC(_COMPILER_VERSION/10 % 10) +# define COMPILER_VERSION_PATCH DEC(_COMPILER_VERSION % 10) +# endif + +/* This compiler is either not known or is too old to define an + identification macro. Try to identify the platform and guess that + it is the native compiler. */ +#elif defined(__sgi) +# define COMPILER_ID "MIPSpro" + +#elif defined(__hpux) || defined(__hpua) +# define COMPILER_ID "HP" + +#else /* unknown compiler */ +# define COMPILER_ID "" + +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_compiler = "INFO" ":" "compiler[" COMPILER_ID "]"; + +/* Identify known platforms by name. */ +#if defined(__linux) || defined(__linux__) || defined(linux) +# define PLATFORM_ID "Linux" + +#elif defined(__CYGWIN__) +# define PLATFORM_ID "Cygwin" + +#elif defined(__MINGW32__) +# define PLATFORM_ID "MinGW" + +#elif defined(__APPLE__) +# define PLATFORM_ID "Darwin" + +#elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32) +# define PLATFORM_ID "Windows" + +#elif defined(__FreeBSD__) || defined(__FreeBSD) +# define PLATFORM_ID "FreeBSD" + +#elif defined(__NetBSD__) || defined(__NetBSD) +# define PLATFORM_ID "NetBSD" + +#elif defined(__OpenBSD__) || defined(__OPENBSD) +# define PLATFORM_ID "OpenBSD" + +#elif defined(__sun) || defined(sun) +# define PLATFORM_ID "SunOS" + +#elif defined(_AIX) || defined(__AIX) || defined(__AIX__) || defined(__aix) || defined(__aix__) +# define PLATFORM_ID "AIX" + +#elif defined(__sgi) || defined(__sgi__) || defined(_SGI) +# define PLATFORM_ID "IRIX" + +#elif defined(__hpux) || defined(__hpux__) +# define PLATFORM_ID "HP-UX" + +#elif defined(__HAIKU__) +# define PLATFORM_ID "Haiku" + +#elif defined(__BeOS) || defined(__BEOS__) || defined(_BEOS) +# define PLATFORM_ID "BeOS" + +#elif defined(__QNX__) || defined(__QNXNTO__) +# define PLATFORM_ID "QNX" + +#elif defined(__tru64) || defined(_tru64) || defined(__TRU64__) +# define PLATFORM_ID "Tru64" + +#elif defined(__riscos) || defined(__riscos__) +# define PLATFORM_ID "RISCos" + +#elif defined(__sinix) || defined(__sinix__) || defined(__SINIX__) +# define PLATFORM_ID "SINIX" + +#elif defined(__UNIX_SV__) +# define PLATFORM_ID "UNIX_SV" + +#elif defined(__bsdos__) +# define PLATFORM_ID "BSDOS" + +#elif defined(_MPRAS) || defined(MPRAS) +# define PLATFORM_ID "MP-RAS" + +#elif defined(__osf) || defined(__osf__) +# define PLATFORM_ID "OSF1" + +#elif defined(_SCO_SV) || defined(SCO_SV) || defined(sco_sv) +# define PLATFORM_ID "SCO_SV" + +#elif defined(__ultrix) || defined(__ultrix__) || defined(_ULTRIX) +# define PLATFORM_ID "ULTRIX" + +#elif defined(__XENIX__) || defined(_XENIX) || defined(XENIX) +# define PLATFORM_ID "Xenix" + +#else /* unknown platform */ +# define PLATFORM_ID "" + +#endif + +/* For windows compilers MSVC and Intel we can determine + the architecture of the compiler being used. This is because + the compilers do not have flags that can change the architecture, + but rather depend on which compiler is being used +*/ +#if defined(_WIN32) && defined(_MSC_VER) +# if defined(_M_IA64) +# define ARCHITECTURE_ID "IA64" + +# elif defined(_M_X64) || defined(_M_AMD64) +# define ARCHITECTURE_ID "x64" + +# elif defined(_M_IX86) +# define ARCHITECTURE_ID "X86" + +# elif defined(_M_ARM) +# define ARCHITECTURE_ID "ARM" + +# elif defined(_M_MIPS) +# define ARCHITECTURE_ID "MIPS" + +# elif defined(_M_SH) +# define ARCHITECTURE_ID "SHx" + +# else /* unknown architecture */ +# define ARCHITECTURE_ID "" +# endif + +#else +# define ARCHITECTURE_ID "" +#endif + +/* Convert integer to decimal digit literals. */ +#define DEC(n) \ + ('0' + (((n) / 10000000)%10)), \ + ('0' + (((n) / 1000000)%10)), \ + ('0' + (((n) / 100000)%10)), \ + ('0' + (((n) / 10000)%10)), \ + ('0' + (((n) / 1000)%10)), \ + ('0' + (((n) / 100)%10)), \ + ('0' + (((n) / 10)%10)), \ + ('0' + ((n) % 10)) + +/* Convert integer to hex digit literals. */ +#define HEX(n) \ + ('0' + ((n)>>28 & 0xF)), \ + ('0' + ((n)>>24 & 0xF)), \ + ('0' + ((n)>>20 & 0xF)), \ + ('0' + ((n)>>16 & 0xF)), \ + ('0' + ((n)>>12 & 0xF)), \ + ('0' + ((n)>>8 & 0xF)), \ + ('0' + ((n)>>4 & 0xF)), \ + ('0' + ((n) & 0xF)) + +/* Construct a string literal encoding the version number components. */ +#ifdef COMPILER_VERSION_MAJOR +char const info_version[] = { + 'I', 'N', 'F', 'O', ':', + 'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','[', + COMPILER_VERSION_MAJOR, +# ifdef COMPILER_VERSION_MINOR + '.', COMPILER_VERSION_MINOR, +# ifdef COMPILER_VERSION_PATCH + '.', COMPILER_VERSION_PATCH, +# ifdef COMPILER_VERSION_TWEAK + '.', COMPILER_VERSION_TWEAK, +# endif +# endif +# endif + ']','\0'}; +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_platform = "INFO" ":" "platform[" PLATFORM_ID "]"; +char const* info_arch = "INFO" ":" "arch[" ARCHITECTURE_ID "]"; + + + +/*--------------------------------------------------------------------------*/ + +int main(int argc, char* argv[]) +{ + int require = 0; + require += info_compiler[argc]; + require += info_platform[argc]; +#ifdef COMPILER_VERSION_MAJOR + require += info_version[argc]; +#endif + (void)argv; + return require; +} diff --git a/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CompilerIdCXX/a.out b/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CompilerIdCXX/a.out new file mode 100755 index 00000000..96c16077 Binary files /dev/null and b/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CompilerIdCXX/a.out differ diff --git a/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeDirectoryInformation.cmake b/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeDirectoryInformation.cmake new file mode 100644 index 00000000..29e5b04a --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeDirectoryInformation.cmake @@ -0,0 +1,16 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Relative path conversion top directories. +SET(CMAKE_RELATIVE_PATH_TOP_SOURCE "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2") +SET(CMAKE_RELATIVE_PATH_TOP_BINARY "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build") + +# Force unix paths in dependencies. +SET(CMAKE_FORCE_UNIX_PATHS 1) + + +# The C and CXX include file regular expressions for this directory. +SET(CMAKE_C_INCLUDE_REGEX_SCAN "^.*$") +SET(CMAKE_C_INCLUDE_REGEX_COMPLAIN "^$") +SET(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN}) +SET(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN}) diff --git a/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeOutput.log b/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeOutput.log new file mode 100644 index 00000000..245ea626 --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeOutput.log @@ -0,0 +1,263 @@ +The system is: Linux - 4.4.0-94-generic - x86_64 +Compiling the C compiler identification source file "CMakeCCompilerId.c" succeeded. +Compiler: /usr/bin/cc +Build flags: +Id flags: + +The output was: +0 + + +Compilation of the C compiler identification source "CMakeCCompilerId.c" produced "a.out" + +The C compiler identification is GNU, found in "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CompilerIdC/a.out" + +Compiling the CXX compiler identification source file "CMakeCXXCompilerId.cpp" succeeded. +Compiler: /usr/bin/c++ +Build flags: +Id flags: + +The output was: +0 + + +Compilation of the CXX compiler identification source "CMakeCXXCompilerId.cpp" produced "a.out" + +The CXX compiler identification is GNU, found in "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles/2.8.12.2/CompilerIdCXX/a.out" + +Determining if the C compiler works passed with the following output: +Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeTmp + +Run Build Command:/usr/bin/make "cmTryCompileExec1587399571/fast" +/usr/bin/make -f CMakeFiles/cmTryCompileExec1587399571.dir/build.make CMakeFiles/cmTryCompileExec1587399571.dir/build +make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeTmp' +/usr/bin/cmake -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeTmp/CMakeFiles" 1 +Building C object CMakeFiles/cmTryCompileExec1587399571.dir/testCCompiler.c.o +/usr/bin/cc -o CMakeFiles/cmTryCompileExec1587399571.dir/testCCompiler.c.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeTmp/testCCompiler.c" +Linking C executable cmTryCompileExec1587399571 +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec1587399571.dir/link.txt --verbose=1 +/usr/bin/cc CMakeFiles/cmTryCompileExec1587399571.dir/testCCompiler.c.o -o cmTryCompileExec1587399571 -rdynamic +make[1]: Leaving directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeTmp' + + +Detecting C compiler ABI info compiled with the following output: +Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeTmp + +Run Build Command:/usr/bin/make "cmTryCompileExec52454330/fast" +/usr/bin/make -f CMakeFiles/cmTryCompileExec52454330.dir/build.make CMakeFiles/cmTryCompileExec52454330.dir/build +make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeTmp' +/usr/bin/cmake -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeTmp/CMakeFiles" 1 +Building C object CMakeFiles/cmTryCompileExec52454330.dir/CMakeCCompilerABI.c.o +/usr/bin/cc -o CMakeFiles/cmTryCompileExec52454330.dir/CMakeCCompilerABI.c.o -c /usr/share/cmake-2.8/Modules/CMakeCCompilerABI.c +Linking C executable cmTryCompileExec52454330 +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec52454330.dir/link.txt --verbose=1 +/usr/bin/cc -v CMakeFiles/cmTryCompileExec52454330.dir/CMakeCCompilerABI.c.o -o cmTryCompileExec52454330 -rdynamic +Using built-in specs. +COLLECT_GCC=/usr/bin/cc +COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/4.8/lto-wrapper +Target: x86_64-linux-gnu +Configured with: ../src/configure -v --with-pkgversion='Ubuntu 4.8.4-2ubuntu1~14.04.3' --with-bugurl=file:///usr/share/doc/gcc-4.8/README.Bugs --enable-languages=c,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-4.8 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --with-gxx-include-dir=/usr/include/c++/4.8 --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --enable-gnu-unique-object --disable-libmudflap --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-4.8-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu +Thread model: posix +gcc version 4.8.4 (Ubuntu 4.8.4-2ubuntu1~14.04.3) +COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/ +LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../:/lib/:/usr/lib/ +COLLECT_GCC_OPTIONS='-v' '-o' 'cmTryCompileExec52454330' '-rdynamic' '-mtune=generic' '-march=x86-64' + /usr/lib/gcc/x86_64-linux-gnu/4.8/collect2 --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTryCompileExec52454330 /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/4.8 -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../.. CMakeFiles/cmTryCompileExec52454330.dir/CMakeCCompilerABI.c.o -lgcc --as-needed -lgcc_s --no-as-needed -lc -lgcc --as-needed -lgcc_s --no-as-needed /usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o +make[1]: Leaving directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeTmp' + + +Parsed C implicit link information from above output: + link line regex: [^( *|.*[/\])(ld|([^/\]+-)?ld|collect2)[^/\]*( |$)] + ignore line: [Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeTmp] + ignore line: [] + ignore line: [Run Build Command:/usr/bin/make "cmTryCompileExec52454330/fast"] + ignore line: [/usr/bin/make -f CMakeFiles/cmTryCompileExec52454330.dir/build.make CMakeFiles/cmTryCompileExec52454330.dir/build] + ignore line: [make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeTmp'] + ignore line: [/usr/bin/cmake -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeTmp/CMakeFiles" 1] + ignore line: [Building C object CMakeFiles/cmTryCompileExec52454330.dir/CMakeCCompilerABI.c.o] + ignore line: [/usr/bin/cc -o CMakeFiles/cmTryCompileExec52454330.dir/CMakeCCompilerABI.c.o -c /usr/share/cmake-2.8/Modules/CMakeCCompilerABI.c] + ignore line: [Linking C executable cmTryCompileExec52454330] + ignore line: [/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec52454330.dir/link.txt --verbose=1] + ignore line: [/usr/bin/cc -v CMakeFiles/cmTryCompileExec52454330.dir/CMakeCCompilerABI.c.o -o cmTryCompileExec52454330 -rdynamic ] + ignore line: [Using built-in specs.] + ignore line: [COLLECT_GCC=/usr/bin/cc] + ignore line: [COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/4.8/lto-wrapper] + ignore line: [Target: x86_64-linux-gnu] + ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 4.8.4-2ubuntu1~14.04.3' --with-bugurl=file:///usr/share/doc/gcc-4.8/README.Bugs --enable-languages=c,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-4.8 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --with-gxx-include-dir=/usr/include/c++/4.8 --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --enable-gnu-unique-object --disable-libmudflap --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-4.8-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu] + ignore line: [Thread model: posix] + ignore line: [gcc version 4.8.4 (Ubuntu 4.8.4-2ubuntu1~14.04.3) ] + ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/] + ignore line: [LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../:/lib/:/usr/lib/] + ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'cmTryCompileExec52454330' '-rdynamic' '-mtune=generic' '-march=x86-64'] + link line: [ /usr/lib/gcc/x86_64-linux-gnu/4.8/collect2 --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTryCompileExec52454330 /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/4.8 -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../.. CMakeFiles/cmTryCompileExec52454330.dir/CMakeCCompilerABI.c.o -lgcc --as-needed -lgcc_s --no-as-needed -lc -lgcc --as-needed -lgcc_s --no-as-needed /usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o] + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/collect2] ==> ignore + arg [--sysroot=/] ==> ignore + arg [--build-id] ==> ignore + arg [--eh-frame-hdr] ==> ignore + arg [-m] ==> ignore + arg [elf_x86_64] ==> ignore + arg [--hash-style=gnu] ==> ignore + arg [--as-needed] ==> ignore + arg [-export-dynamic] ==> ignore + arg [-dynamic-linker] ==> ignore + arg [/lib64/ld-linux-x86-64.so.2] ==> ignore + arg [-zrelro] ==> ignore + arg [-o] ==> ignore + arg [cmTryCompileExec52454330] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o] ==> ignore + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] + arg [-L/lib/x86_64-linux-gnu] ==> dir [/lib/x86_64-linux-gnu] + arg [-L/lib/../lib] ==> dir [/lib/../lib] + arg [-L/usr/lib/x86_64-linux-gnu] ==> dir [/usr/lib/x86_64-linux-gnu] + arg [-L/usr/lib/../lib] ==> dir [/usr/lib/../lib] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] + arg [CMakeFiles/cmTryCompileExec52454330.dir/CMakeCCompilerABI.c.o] ==> ignore + arg [-lgcc] ==> lib [gcc] + arg [--as-needed] ==> ignore + arg [-lgcc_s] ==> lib [gcc_s] + arg [--no-as-needed] ==> ignore + arg [-lc] ==> lib [c] + arg [-lgcc] ==> lib [gcc] + arg [--as-needed] ==> ignore + arg [-lgcc_s] ==> lib [gcc_s] + arg [--no-as-needed] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o] ==> ignore + remove lib [gcc] + remove lib [gcc_s] + remove lib [gcc] + remove lib [gcc_s] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8] ==> [/usr/lib/gcc/x86_64-linux-gnu/4.8] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] ==> [/usr/lib] + collapse library dir [/lib/x86_64-linux-gnu] ==> [/lib/x86_64-linux-gnu] + collapse library dir [/lib/../lib] ==> [/lib] + collapse library dir [/usr/lib/x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/../lib] ==> [/usr/lib] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] ==> [/usr/lib] + implicit libs: [c] + implicit dirs: [/usr/lib/gcc/x86_64-linux-gnu/4.8;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib] + implicit fwks: [] + + +Determining if the CXX compiler works passed with the following output: +Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeTmp + +Run Build Command:/usr/bin/make "cmTryCompileExec3189177864/fast" +/usr/bin/make -f CMakeFiles/cmTryCompileExec3189177864.dir/build.make CMakeFiles/cmTryCompileExec3189177864.dir/build +make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeTmp' +/usr/bin/cmake -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeTmp/CMakeFiles" 1 +Building CXX object CMakeFiles/cmTryCompileExec3189177864.dir/testCXXCompiler.cxx.o +/usr/bin/c++ -o CMakeFiles/cmTryCompileExec3189177864.dir/testCXXCompiler.cxx.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeTmp/testCXXCompiler.cxx" +Linking CXX executable cmTryCompileExec3189177864 +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec3189177864.dir/link.txt --verbose=1 +/usr/bin/c++ CMakeFiles/cmTryCompileExec3189177864.dir/testCXXCompiler.cxx.o -o cmTryCompileExec3189177864 -rdynamic +make[1]: Leaving directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeTmp' + + +Detecting CXX compiler ABI info compiled with the following output: +Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeTmp + +Run Build Command:/usr/bin/make "cmTryCompileExec3410755104/fast" +/usr/bin/make -f CMakeFiles/cmTryCompileExec3410755104.dir/build.make CMakeFiles/cmTryCompileExec3410755104.dir/build +make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeTmp' +/usr/bin/cmake -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeTmp/CMakeFiles" 1 +Building CXX object CMakeFiles/cmTryCompileExec3410755104.dir/CMakeCXXCompilerABI.cpp.o +/usr/bin/c++ -o CMakeFiles/cmTryCompileExec3410755104.dir/CMakeCXXCompilerABI.cpp.o -c /usr/share/cmake-2.8/Modules/CMakeCXXCompilerABI.cpp +Linking CXX executable cmTryCompileExec3410755104 +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec3410755104.dir/link.txt --verbose=1 +/usr/bin/c++ -v CMakeFiles/cmTryCompileExec3410755104.dir/CMakeCXXCompilerABI.cpp.o -o cmTryCompileExec3410755104 -rdynamic +Using built-in specs. +COLLECT_GCC=/usr/bin/c++ +COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/4.8/lto-wrapper +Target: x86_64-linux-gnu +Configured with: ../src/configure -v --with-pkgversion='Ubuntu 4.8.4-2ubuntu1~14.04.3' --with-bugurl=file:///usr/share/doc/gcc-4.8/README.Bugs --enable-languages=c,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-4.8 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --with-gxx-include-dir=/usr/include/c++/4.8 --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --enable-gnu-unique-object --disable-libmudflap --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-4.8-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu +Thread model: posix +gcc version 4.8.4 (Ubuntu 4.8.4-2ubuntu1~14.04.3) +COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/ +LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../:/lib/:/usr/lib/ +COLLECT_GCC_OPTIONS='-v' '-o' 'cmTryCompileExec3410755104' '-rdynamic' '-shared-libgcc' '-mtune=generic' '-march=x86-64' + /usr/lib/gcc/x86_64-linux-gnu/4.8/collect2 --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTryCompileExec3410755104 /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/4.8 -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../.. CMakeFiles/cmTryCompileExec3410755104.dir/CMakeCXXCompilerABI.cpp.o -lstdc++ -lm -lgcc_s -lgcc -lc -lgcc_s -lgcc /usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o +make[1]: Leaving directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeTmp' + + +Parsed CXX implicit link information from above output: + link line regex: [^( *|.*[/\])(ld|([^/\]+-)?ld|collect2)[^/\]*( |$)] + ignore line: [Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeTmp] + ignore line: [] + ignore line: [Run Build Command:/usr/bin/make "cmTryCompileExec3410755104/fast"] + ignore line: [/usr/bin/make -f CMakeFiles/cmTryCompileExec3410755104.dir/build.make CMakeFiles/cmTryCompileExec3410755104.dir/build] + ignore line: [make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeTmp'] + ignore line: [/usr/bin/cmake -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles/CMakeTmp/CMakeFiles" 1] + ignore line: [Building CXX object CMakeFiles/cmTryCompileExec3410755104.dir/CMakeCXXCompilerABI.cpp.o] + ignore line: [/usr/bin/c++ -o CMakeFiles/cmTryCompileExec3410755104.dir/CMakeCXXCompilerABI.cpp.o -c /usr/share/cmake-2.8/Modules/CMakeCXXCompilerABI.cpp] + ignore line: [Linking CXX executable cmTryCompileExec3410755104] + ignore line: [/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec3410755104.dir/link.txt --verbose=1] + ignore line: [/usr/bin/c++ -v CMakeFiles/cmTryCompileExec3410755104.dir/CMakeCXXCompilerABI.cpp.o -o cmTryCompileExec3410755104 -rdynamic ] + ignore line: [Using built-in specs.] + ignore line: [COLLECT_GCC=/usr/bin/c++] + ignore line: [COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/4.8/lto-wrapper] + ignore line: [Target: x86_64-linux-gnu] + ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 4.8.4-2ubuntu1~14.04.3' --with-bugurl=file:///usr/share/doc/gcc-4.8/README.Bugs --enable-languages=c,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-4.8 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --with-gxx-include-dir=/usr/include/c++/4.8 --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --enable-gnu-unique-object --disable-libmudflap --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-4.8-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu] + ignore line: [Thread model: posix] + ignore line: [gcc version 4.8.4 (Ubuntu 4.8.4-2ubuntu1~14.04.3) ] + ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/] + ignore line: [LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../:/lib/:/usr/lib/] + ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'cmTryCompileExec3410755104' '-rdynamic' '-shared-libgcc' '-mtune=generic' '-march=x86-64'] + link line: [ /usr/lib/gcc/x86_64-linux-gnu/4.8/collect2 --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTryCompileExec3410755104 /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/4.8 -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../.. CMakeFiles/cmTryCompileExec3410755104.dir/CMakeCXXCompilerABI.cpp.o -lstdc++ -lm -lgcc_s -lgcc -lc -lgcc_s -lgcc /usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o] + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/collect2] ==> ignore + arg [--sysroot=/] ==> ignore + arg [--build-id] ==> ignore + arg [--eh-frame-hdr] ==> ignore + arg [-m] ==> ignore + arg [elf_x86_64] ==> ignore + arg [--hash-style=gnu] ==> ignore + arg [--as-needed] ==> ignore + arg [-export-dynamic] ==> ignore + arg [-dynamic-linker] ==> ignore + arg [/lib64/ld-linux-x86-64.so.2] ==> ignore + arg [-zrelro] ==> ignore + arg [-o] ==> ignore + arg [cmTryCompileExec3410755104] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o] ==> ignore + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] + arg [-L/lib/x86_64-linux-gnu] ==> dir [/lib/x86_64-linux-gnu] + arg [-L/lib/../lib] ==> dir [/lib/../lib] + arg [-L/usr/lib/x86_64-linux-gnu] ==> dir [/usr/lib/x86_64-linux-gnu] + arg [-L/usr/lib/../lib] ==> dir [/usr/lib/../lib] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] + arg [CMakeFiles/cmTryCompileExec3410755104.dir/CMakeCXXCompilerABI.cpp.o] ==> ignore + arg [-lstdc++] ==> lib [stdc++] + arg [-lm] ==> lib [m] + arg [-lgcc_s] ==> lib [gcc_s] + arg [-lgcc] ==> lib [gcc] + arg [-lc] ==> lib [c] + arg [-lgcc_s] ==> lib [gcc_s] + arg [-lgcc] ==> lib [gcc] + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o] ==> ignore + remove lib [gcc_s] + remove lib [gcc] + remove lib [gcc_s] + remove lib [gcc] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8] ==> [/usr/lib/gcc/x86_64-linux-gnu/4.8] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] ==> [/usr/lib] + collapse library dir [/lib/x86_64-linux-gnu] ==> [/lib/x86_64-linux-gnu] + collapse library dir [/lib/../lib] ==> [/lib] + collapse library dir [/usr/lib/x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/../lib] ==> [/usr/lib] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] ==> [/usr/lib] + implicit libs: [stdc++;m;c] + implicit dirs: [/usr/lib/gcc/x86_64-linux-gnu/4.8;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib] + implicit fwks: [] + + diff --git a/vSLAM/ch9 project/0.2/build/CMakeFiles/Makefile.cmake b/vSLAM/ch9 project/0.2/build/CMakeFiles/Makefile.cmake new file mode 100644 index 00000000..7931ed07 --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/CMakeFiles/Makefile.cmake @@ -0,0 +1,54 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# The generator used is: +SET(CMAKE_DEPENDS_GENERATOR "Unix Makefiles") + +# The top level Makefile was generated from the following files: +SET(CMAKE_MAKEFILE_DEPENDS + "CMakeCache.txt" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build/SophusConfig.cmake" + "../CMakeLists.txt" + "CMakeFiles/2.8.12.2/CMakeCCompiler.cmake" + "CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake" + "CMakeFiles/2.8.12.2/CMakeSystem.cmake" + "../cmake_modules/FindG2O.cmake" + "../src/CMakeLists.txt" + "../test/CMakeLists.txt" + "/usr/local/share/OpenCV/OpenCVConfig-version.cmake" + "/usr/local/share/OpenCV/OpenCVConfig.cmake" + "/usr/local/share/OpenCV/OpenCVModules-release.cmake" + "/usr/local/share/OpenCV/OpenCVModules.cmake" + "/usr/share/cmake-2.8/Modules/CMakeCInformation.cmake" + "/usr/share/cmake-2.8/Modules/CMakeCXXInformation.cmake" + "/usr/share/cmake-2.8/Modules/CMakeCommonLanguageInclude.cmake" + "/usr/share/cmake-2.8/Modules/CMakeGenericSystem.cmake" + "/usr/share/cmake-2.8/Modules/CMakeSystemSpecificInformation.cmake" + "/usr/share/cmake-2.8/Modules/Compiler/GNU-C.cmake" + "/usr/share/cmake-2.8/Modules/Compiler/GNU-CXX.cmake" + "/usr/share/cmake-2.8/Modules/Compiler/GNU.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux-GNU-C.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux-GNU-CXX.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux-GNU.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux.cmake" + "/usr/share/cmake-2.8/Modules/Platform/UnixPaths.cmake" + ) + +# The corresponding makefile is: +SET(CMAKE_MAKEFILE_OUTPUTS + "Makefile" + "CMakeFiles/cmake.check_cache" + ) + +# Byproducts of CMake generate step: +SET(CMAKE_MAKEFILE_PRODUCTS + "CMakeFiles/CMakeDirectoryInformation.cmake" + "src/CMakeFiles/CMakeDirectoryInformation.cmake" + "test/CMakeFiles/CMakeDirectoryInformation.cmake" + ) + +# Dependency information for all targets: +SET(CMAKE_DEPEND_INFO_FILES + "src/CMakeFiles/myslam.dir/DependInfo.cmake" + "test/CMakeFiles/run_vo.dir/DependInfo.cmake" + ) diff --git a/vSLAM/ch9 project/0.2/build/CMakeFiles/Makefile2 b/vSLAM/ch9 project/0.2/build/CMakeFiles/Makefile2 new file mode 100644 index 00000000..94ab8708 --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/CMakeFiles/Makefile2 @@ -0,0 +1,164 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Default target executed when no arguments are given to make. +default_target: all +.PHONY : default_target + +# The main recursive all target +all: +.PHONY : all + +# The main recursive preinstall target +preinstall: +.PHONY : preinstall + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2" + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" + +#============================================================================= +# Directory level rules for directory src + +# Convenience name for "all" pass in the directory. +src/all: src/CMakeFiles/myslam.dir/all +.PHONY : src/all + +# Convenience name for "clean" pass in the directory. +src/clean: src/CMakeFiles/myslam.dir/clean +.PHONY : src/clean + +# Convenience name for "preinstall" pass in the directory. +src/preinstall: +.PHONY : src/preinstall + +#============================================================================= +# Target rules for target src/CMakeFiles/myslam.dir + +# All Build rule for target. +src/CMakeFiles/myslam.dir/all: + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/depend + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/build + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles" 1 2 3 4 5 6 + @echo "Built target myslam" +.PHONY : src/CMakeFiles/myslam.dir/all + +# Include target in all. +all: src/CMakeFiles/myslam.dir/all +.PHONY : all + +# Build rule for subdir invocation for target. +src/CMakeFiles/myslam.dir/rule: cmake_check_build_system + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles" 6 + $(MAKE) -f CMakeFiles/Makefile2 src/CMakeFiles/myslam.dir/all + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles" 0 +.PHONY : src/CMakeFiles/myslam.dir/rule + +# Convenience name for target. +myslam: src/CMakeFiles/myslam.dir/rule +.PHONY : myslam + +# clean rule for target. +src/CMakeFiles/myslam.dir/clean: + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/clean +.PHONY : src/CMakeFiles/myslam.dir/clean + +# clean rule for target. +clean: src/CMakeFiles/myslam.dir/clean +.PHONY : clean + +#============================================================================= +# Directory level rules for directory test + +# Convenience name for "all" pass in the directory. +test/all: test/CMakeFiles/run_vo.dir/all +.PHONY : test/all + +# Convenience name for "clean" pass in the directory. +test/clean: test/CMakeFiles/run_vo.dir/clean +.PHONY : test/clean + +# Convenience name for "preinstall" pass in the directory. +test/preinstall: +.PHONY : test/preinstall + +#============================================================================= +# Target rules for target test/CMakeFiles/run_vo.dir + +# All Build rule for target. +test/CMakeFiles/run_vo.dir/all: src/CMakeFiles/myslam.dir/all + $(MAKE) -f test/CMakeFiles/run_vo.dir/build.make test/CMakeFiles/run_vo.dir/depend + $(MAKE) -f test/CMakeFiles/run_vo.dir/build.make test/CMakeFiles/run_vo.dir/build + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles" 7 + @echo "Built target run_vo" +.PHONY : test/CMakeFiles/run_vo.dir/all + +# Include target in all. +all: test/CMakeFiles/run_vo.dir/all +.PHONY : all + +# Build rule for subdir invocation for target. +test/CMakeFiles/run_vo.dir/rule: cmake_check_build_system + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles" 7 + $(MAKE) -f CMakeFiles/Makefile2 test/CMakeFiles/run_vo.dir/all + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles" 0 +.PHONY : test/CMakeFiles/run_vo.dir/rule + +# Convenience name for target. +run_vo: test/CMakeFiles/run_vo.dir/rule +.PHONY : run_vo + +# clean rule for target. +test/CMakeFiles/run_vo.dir/clean: + $(MAKE) -f test/CMakeFiles/run_vo.dir/build.make test/CMakeFiles/run_vo.dir/clean +.PHONY : test/CMakeFiles/run_vo.dir/clean + +# clean rule for target. +clean: test/CMakeFiles/run_vo.dir/clean +.PHONY : clean + +#============================================================================= +# Special targets to cleanup operation of make. + +# Special rule to run CMake to check the build system integrity. +# No rule that depends on this can have commands that come from listfiles +# because they might be regenerated. +cmake_check_build_system: + $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0 +.PHONY : cmake_check_build_system + diff --git a/vSLAM/ch9 project/0.2/build/CMakeFiles/TargetDirectories.txt b/vSLAM/ch9 project/0.2/build/CMakeFiles/TargetDirectories.txt new file mode 100644 index 00000000..efe540ac --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/CMakeFiles/TargetDirectories.txt @@ -0,0 +1,2 @@ +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir diff --git a/vSLAM/ch9 project/0.2/build/CMakeFiles/cmake.check_cache b/vSLAM/ch9 project/0.2/build/CMakeFiles/cmake.check_cache new file mode 100644 index 00000000..3dccd731 --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/CMakeFiles/cmake.check_cache @@ -0,0 +1 @@ +# This file is generated by cmake for dependency checking of the CMakeCache.txt file diff --git a/vSLAM/ch9 project/0.2/build/CMakeFiles/progress.marks b/vSLAM/ch9 project/0.2/build/CMakeFiles/progress.marks new file mode 100644 index 00000000..7f8f011e --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/CMakeFiles/progress.marks @@ -0,0 +1 @@ +7 diff --git a/vSLAM/ch9 project/0.2/build/Makefile b/vSLAM/ch9 project/0.2/build/Makefile new file mode 100644 index 00000000..ac43b954 --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/Makefile @@ -0,0 +1,150 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Default target executed when no arguments are given to make. +default_target: all +.PHONY : default_target + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2" + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" + +#============================================================================= +# Targets provided globally by CMake. + +# Special rule for the target edit_cache +edit_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running interactive CMake command-line interface..." + /usr/bin/cmake -i . +.PHONY : edit_cache + +# Special rule for the target edit_cache +edit_cache/fast: edit_cache +.PHONY : edit_cache/fast + +# Special rule for the target rebuild_cache +rebuild_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake to regenerate build system..." + /usr/bin/cmake -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) +.PHONY : rebuild_cache + +# Special rule for the target rebuild_cache +rebuild_cache/fast: rebuild_cache +.PHONY : rebuild_cache/fast + +# The main all target +all: cmake_check_build_system + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles/progress.marks" + $(MAKE) -f CMakeFiles/Makefile2 all + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles" 0 +.PHONY : all + +# The main clean target +clean: + $(MAKE) -f CMakeFiles/Makefile2 clean +.PHONY : clean + +# The main clean target +clean/fast: clean +.PHONY : clean/fast + +# Prepare targets for installation. +preinstall: all + $(MAKE) -f CMakeFiles/Makefile2 preinstall +.PHONY : preinstall + +# Prepare targets for installation. +preinstall/fast: + $(MAKE) -f CMakeFiles/Makefile2 preinstall +.PHONY : preinstall/fast + +# clear depends +depend: + $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 1 +.PHONY : depend + +#============================================================================= +# Target rules for targets named myslam + +# Build rule for target. +myslam: cmake_check_build_system + $(MAKE) -f CMakeFiles/Makefile2 myslam +.PHONY : myslam + +# fast build rule for target. +myslam/fast: + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/build +.PHONY : myslam/fast + +#============================================================================= +# Target rules for targets named run_vo + +# Build rule for target. +run_vo: cmake_check_build_system + $(MAKE) -f CMakeFiles/Makefile2 run_vo +.PHONY : run_vo + +# fast build rule for target. +run_vo/fast: + $(MAKE) -f test/CMakeFiles/run_vo.dir/build.make test/CMakeFiles/run_vo.dir/build +.PHONY : run_vo/fast + +# Help Target +help: + @echo "The following are some of the valid targets for this Makefile:" + @echo "... all (the default if no target is provided)" + @echo "... clean" + @echo "... depend" + @echo "... edit_cache" + @echo "... rebuild_cache" + @echo "... myslam" + @echo "... run_vo" +.PHONY : help + + + +#============================================================================= +# Special targets to cleanup operation of make. + +# Special rule to run CMake to check the build system integrity. +# No rule that depends on this can have commands that come from listfiles +# because they might be regenerated. +cmake_check_build_system: + $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0 +.PHONY : cmake_check_build_system + diff --git a/vSLAM/ch9 project/0.2/build/cmake_install.cmake b/vSLAM/ch9 project/0.2/build/cmake_install.cmake new file mode 100644 index 00000000..d9febd31 --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/cmake_install.cmake @@ -0,0 +1,51 @@ +# Install script for directory: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2 + +# Set the install prefix +IF(NOT DEFINED CMAKE_INSTALL_PREFIX) + SET(CMAKE_INSTALL_PREFIX "/usr/local") +ENDIF(NOT DEFINED CMAKE_INSTALL_PREFIX) +STRING(REGEX REPLACE "/$" "" CMAKE_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}") + +# Set the install configuration name. +IF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + IF(BUILD_TYPE) + STRING(REGEX REPLACE "^[^A-Za-z0-9_]+" "" + CMAKE_INSTALL_CONFIG_NAME "${BUILD_TYPE}") + ELSE(BUILD_TYPE) + SET(CMAKE_INSTALL_CONFIG_NAME "Release") + ENDIF(BUILD_TYPE) + MESSAGE(STATUS "Install configuration: \"${CMAKE_INSTALL_CONFIG_NAME}\"") +ENDIF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + +# Set the component getting installed. +IF(NOT CMAKE_INSTALL_COMPONENT) + IF(COMPONENT) + MESSAGE(STATUS "Install component: \"${COMPONENT}\"") + SET(CMAKE_INSTALL_COMPONENT "${COMPONENT}") + ELSE(COMPONENT) + SET(CMAKE_INSTALL_COMPONENT) + ENDIF(COMPONENT) +ENDIF(NOT CMAKE_INSTALL_COMPONENT) + +# Install shared libraries without execute permission? +IF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + SET(CMAKE_INSTALL_SO_NO_EXE "1") +ENDIF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + +IF(NOT CMAKE_INSTALL_LOCAL_ONLY) + # Include the install script for each subdirectory. + INCLUDE("/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src/cmake_install.cmake") + INCLUDE("/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/test/cmake_install.cmake") + +ENDIF(NOT CMAKE_INSTALL_LOCAL_ONLY) + +IF(CMAKE_INSTALL_COMPONENT) + SET(CMAKE_INSTALL_MANIFEST "install_manifest_${CMAKE_INSTALL_COMPONENT}.txt") +ELSE(CMAKE_INSTALL_COMPONENT) + SET(CMAKE_INSTALL_MANIFEST "install_manifest.txt") +ENDIF(CMAKE_INSTALL_COMPONENT) + +FILE(WRITE "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/${CMAKE_INSTALL_MANIFEST}" "") +FOREACH(file ${CMAKE_INSTALL_MANIFEST_FILES}) + FILE(APPEND "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/${CMAKE_INSTALL_MANIFEST}" "${file}\n") +ENDFOREACH(file) diff --git a/vSLAM/ch9 project/0.2/build/src/CMakeFiles/CMakeDirectoryInformation.cmake b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/CMakeDirectoryInformation.cmake new file mode 100644 index 00000000..29e5b04a --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/CMakeDirectoryInformation.cmake @@ -0,0 +1,16 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Relative path conversion top directories. +SET(CMAKE_RELATIVE_PATH_TOP_SOURCE "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2") +SET(CMAKE_RELATIVE_PATH_TOP_BINARY "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build") + +# Force unix paths in dependencies. +SET(CMAKE_FORCE_UNIX_PATHS 1) + + +# The C and CXX include file regular expressions for this directory. +SET(CMAKE_C_INCLUDE_REGEX_SCAN "^.*$") +SET(CMAKE_C_INCLUDE_REGEX_COMPLAIN "^$") +SET(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN}) +SET(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN}) diff --git a/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/CXX.includecache b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/CXX.includecache new file mode 100644 index 00000000..9568724c --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/CXX.includecache @@ -0,0 +1,1570 @@ +#IncludeRegexLine: ^[ ]*#[ ]*(include|import)[ ]*[<"]([^">]+)([">]) + +#IncludeRegexScan: ^.*$ + +#IncludeRegexComplain: ^$ + +#IncludeRegexTransform: + +../include/myslam/camera.h +myslam/common_include.h +../include/myslam/myslam/common_include.h + +../include/myslam/common_include.h +Eigen/Core +- +Eigen/Geometry +- +sophus/se3.h +- +sophus/so3.h +- +opencv2/core/core.hpp +- +vector +- +list +- +memory +- +string +- +iostream +- +set +- +unordered_map +- +map +- + +../include/myslam/config.h +myslam/common_include.h +../include/myslam/myslam/common_include.h + +../include/myslam/frame.h +myslam/common_include.h +../include/myslam/myslam/common_include.h +myslam/camera.h +../include/myslam/myslam/camera.h + +../include/myslam/map.h +myslam/common_include.h +../include/myslam/myslam/common_include.h +myslam/frame.h +../include/myslam/myslam/frame.h +myslam/mappoint.h +../include/myslam/myslam/mappoint.h + +../include/myslam/mappoint.h + +../include/myslam/visual_odometry.h +myslam/common_include.h +../include/myslam/myslam/common_include.h +myslam/map.h +../include/myslam/myslam/map.h +opencv2/features2d/features2d.hpp +- + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +so3.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +Eigen/Core +- +Eigen/StdVector +- +Eigen/Geometry +- + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/visual_odometry.cpp +opencv2/highgui/highgui.hpp +- +opencv2/imgproc/imgproc.hpp +- +opencv2/calib3d/calib3d.hpp +- +algorithm +- +boost/timer.hpp +- +myslam/config.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/myslam/config.h +myslam/visual_odometry.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/myslam/visual_odometry.h + +/usr/include/eigen3/Eigen/Cholesky +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/Cholesky/LLT.h +/usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/Cholesky/LDLT.h +/usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/Cholesky/LLT_MKL.h +/usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Core/util/Macros.h +/usr/include/eigen3/Eigen/src/Core/util/Macros.h +complex +- +src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +malloc.h +- +immintrin.h +- +emmintrin.h +- +xmmintrin.h +- +pmmintrin.h +- +tmmintrin.h +- +smmintrin.h +- +nmmintrin.h +- +altivec.h +- +arm_neon.h +- +omp.h +- +cerrno +- +cstddef +- +cstdlib +- +cmath +- +cassert +- +functional +- +iosfwd +- +cstring +- +string +- +limits +- +climits +- +algorithm +- +iostream +- +intrin.h +- +new +- +src/Core/util/Constants.h +/usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/Core/util/ForwardDeclarations.h +/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/Core/util/Meta.h +/usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/Core/util/StaticAssert.h +/usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/Core/util/XprHelper.h +/usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/Core/util/Memory.h +/usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/Core/NumTraits.h +/usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/Core/MathFunctions.h +/usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/Core/GenericPacketMath.h +/usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/Core/arch/SSE/PacketMath.h +/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/Core/arch/SSE/MathFunctions.h +/usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/Core/arch/SSE/Complex.h +/usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/Core/arch/AltiVec/PacketMath.h +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/Core/arch/AltiVec/Complex.h +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/Core/arch/NEON/PacketMath.h +/usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/Core/arch/NEON/Complex.h +/usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/Core/arch/Default/Settings.h +/usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/Core/Functors.h +/usr/include/eigen3/Eigen/src/Core/Functors.h +src/Core/DenseCoeffsBase.h +/usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/Core/DenseBase.h +/usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/Core/MatrixBase.h +/usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/Core/EigenBase.h +/usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/Core/Assign.h +/usr/include/eigen3/Eigen/src/Core/Assign.h +src/Core/util/BlasUtil.h +/usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/Core/DenseStorage.h +/usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/Core/NestByValue.h +/usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/Core/ForceAlignedAccess.h +/usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/Core/ReturnByValue.h +/usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/Core/NoAlias.h +/usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/Core/PlainObjectBase.h +/usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/Core/Matrix.h +/usr/include/eigen3/Eigen/src/Core/Matrix.h +src/Core/Array.h +/usr/include/eigen3/Eigen/src/Core/Array.h +src/Core/CwiseBinaryOp.h +/usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/Core/CwiseUnaryOp.h +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/Core/CwiseNullaryOp.h +/usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/Core/CwiseUnaryView.h +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/Core/SelfCwiseBinaryOp.h +/usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/Core/Dot.h +/usr/include/eigen3/Eigen/src/Core/Dot.h +src/Core/StableNorm.h +/usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/Core/MapBase.h +/usr/include/eigen3/Eigen/src/Core/MapBase.h +src/Core/Stride.h +/usr/include/eigen3/Eigen/src/Core/Stride.h +src/Core/Map.h +/usr/include/eigen3/Eigen/src/Core/Map.h +src/Core/Block.h +/usr/include/eigen3/Eigen/src/Core/Block.h +src/Core/VectorBlock.h +/usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/Core/Ref.h +/usr/include/eigen3/Eigen/src/Core/Ref.h +src/Core/Transpose.h +/usr/include/eigen3/Eigen/src/Core/Transpose.h +src/Core/DiagonalMatrix.h +/usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/Core/Diagonal.h +/usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/Core/DiagonalProduct.h +/usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/Core/PermutationMatrix.h +/usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/Core/Transpositions.h +/usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/Core/Redux.h +/usr/include/eigen3/Eigen/src/Core/Redux.h +src/Core/Visitor.h +/usr/include/eigen3/Eigen/src/Core/Visitor.h +src/Core/Fuzzy.h +/usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/Core/IO.h +/usr/include/eigen3/Eigen/src/Core/IO.h +src/Core/Swap.h +/usr/include/eigen3/Eigen/src/Core/Swap.h +src/Core/CommaInitializer.h +/usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/Core/Flagged.h +/usr/include/eigen3/Eigen/src/Core/Flagged.h +src/Core/ProductBase.h +/usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/Core/GeneralProduct.h +/usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/Core/TriangularMatrix.h +/usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/Core/SelfAdjointView.h +/usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/Core/products/GeneralBlockPanelKernel.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/Core/products/Parallelizer.h +/usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/Core/products/CoeffBasedProduct.h +/usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/Core/products/GeneralMatrixVector.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/Core/products/GeneralMatrixMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/Core/SolveTriangular.h +/usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/Core/products/GeneralMatrixMatrixTriangular.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/Core/products/SelfadjointMatrixVector.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/Core/products/SelfadjointMatrixMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/Core/products/SelfadjointProduct.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/Core/products/SelfadjointRank2Update.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/Core/products/TriangularMatrixVector.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/Core/products/TriangularMatrixMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/Core/products/TriangularSolverMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/Core/products/TriangularSolverVector.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/Core/BandMatrix.h +/usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/Core/CoreIterators.h +/usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/Core/BooleanRedux.h +/usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/Core/Select.h +/usr/include/eigen3/Eigen/src/Core/Select.h +src/Core/VectorwiseOp.h +/usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/Core/Random.h +/usr/include/eigen3/Eigen/src/Core/Random.h +src/Core/Replicate.h +/usr/include/eigen3/Eigen/src/Core/Replicate.h +src/Core/Reverse.h +/usr/include/eigen3/Eigen/src/Core/Reverse.h +src/Core/ArrayBase.h +/usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/Core/ArrayWrapper.h +/usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/Core/products/GeneralMatrixMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/Core/products/GeneralMatrixVector_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/Core/products/SelfadjointMatrixMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/Core/products/SelfadjointMatrixVector_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/Core/products/TriangularMatrixMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/Core/products/TriangularMatrixVector_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/Core/products/TriangularSolverMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/Core/Assign_MKL.h +/usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/Core/GlobalFunctions.h +/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +Eigen2Support +/usr/include/eigen3/Eigen/Eigen2Support + +/usr/include/eigen3/Eigen/Eigen2Support +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Eigen2Support/Macros.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/Eigen2Support/Memory.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/Eigen2Support/Meta.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/Eigen2Support/Lazy.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/Eigen2Support/Cwise.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/Eigen2Support/CwiseOperators.h +/usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/Eigen2Support/TriangularSolver.h +/usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/Eigen2Support/Block.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/Eigen2Support/VectorBlock.h +/usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/Eigen2Support/Minor.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/Eigen2Support/MathFunctions.h +/usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +iostream +- + +/usr/include/eigen3/Eigen/Eigenvalues +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +Cholesky +/usr/include/eigen3/Eigen/Cholesky +Jacobi +/usr/include/eigen3/Eigen/Jacobi +Householder +/usr/include/eigen3/Eigen/Householder +LU +/usr/include/eigen3/Eigen/LU +Geometry +/usr/include/eigen3/Eigen/Geometry +src/Eigenvalues/Tridiagonalization.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/Eigenvalues/RealSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/Eigenvalues/EigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/Eigenvalues/SelfAdjointEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/Eigenvalues/HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/Eigenvalues/ComplexSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/Eigenvalues/ComplexEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/Eigenvalues/RealQZ.h +/usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/Eigenvalues/GeneralizedEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/Eigenvalues/MatrixBaseEigenvalues.h +/usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/Eigenvalues/RealSchur_MKL.h +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/Eigenvalues/ComplexSchur_MKL.h +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Geometry +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +SVD +/usr/include/eigen3/Eigen/SVD +LU +/usr/include/eigen3/Eigen/LU +limits +- +src/Geometry/OrthoMethods.h +/usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/Geometry/EulerAngles.h +/usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/Geometry/Homogeneous.h +/usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/Geometry/RotationBase.h +/usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/Geometry/Rotation2D.h +/usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/Geometry/Quaternion.h +/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/Geometry/AngleAxis.h +/usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/Geometry/Transform.h +/usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/Geometry/Translation.h +/usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/Geometry/Scaling.h +/usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/Geometry/Hyperplane.h +/usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/Geometry/ParametrizedLine.h +/usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/Geometry/AlignedBox.h +/usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/Geometry/Umeyama.h +/usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/Geometry/arch/Geometry_SSE.h +/usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/Eigen2Support/Geometry/All.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Householder +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Householder/Householder.h +/usr/include/eigen3/Eigen/src/Householder/Householder.h +src/Householder/HouseholderSequence.h +/usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/Householder/BlockHouseholder.h +/usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Jacobi +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Jacobi/Jacobi.h +/usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/LU +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/misc/Kernel.h +/usr/include/eigen3/Eigen/src/misc/Kernel.h +src/misc/Image.h +/usr/include/eigen3/Eigen/src/misc/Image.h +src/LU/FullPivLU.h +/usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/LU/PartialPivLU.h +/usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/LU/PartialPivLU_MKL.h +/usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/LU/Determinant.h +/usr/include/eigen3/Eigen/src/LU/Determinant.h +src/LU/Inverse.h +/usr/include/eigen3/Eigen/src/LU/Inverse.h +src/LU/arch/Inverse_SSE.h +/usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/Eigen2Support/LU.h +/usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/QR +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +Cholesky +/usr/include/eigen3/Eigen/Cholesky +Jacobi +/usr/include/eigen3/Eigen/Jacobi +Householder +/usr/include/eigen3/Eigen/Householder +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/QR/HouseholderQR.h +/usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/QR/FullPivHouseholderQR.h +/usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/QR/ColPivHouseholderQR.h +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/QR/HouseholderQR_MKL.h +/usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/QR/ColPivHouseholderQR_MKL.h +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/Eigen2Support/QR.h +/usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +Eigenvalues +/usr/include/eigen3/Eigen/Eigenvalues + +/usr/include/eigen3/Eigen/SVD +QR +/usr/include/eigen3/Eigen/QR +Householder +/usr/include/eigen3/Eigen/Householder +Jacobi +/usr/include/eigen3/Eigen/Jacobi +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/SVD/JacobiSVD.h +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/SVD/JacobiSVD_MKL.h +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/SVD/UpperBidiagonalization.h +/usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/Eigen2Support/SVD.h +/usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/StdVector +Core +/usr/include/eigen3/Eigen/Core +vector +- +src/StlSupport/StdVector.h +/usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + +/usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + +/usr/include/eigen3/Eigen/src/Cholesky/LLT.h + +/usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Cholesky/Eigen/src/Core/util/MKL_support.h +iostream +- + +/usr/include/eigen3/Eigen/src/Core/Array.h + +/usr/include/eigen3/Eigen/src/Core/ArrayBase.h +../plugins/CommonCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +../plugins/MatrixCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +../plugins/ArrayCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +../plugins/CommonCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +../plugins/MatrixCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +../plugins/ArrayCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + +/usr/include/eigen3/Eigen/src/Core/Assign.h + +/usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + +/usr/include/eigen3/Eigen/src/Core/BandMatrix.h + +/usr/include/eigen3/Eigen/src/Core/Block.h + +/usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + +/usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + +/usr/include/eigen3/Eigen/src/Core/CoreIterators.h + +/usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + +/usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + +/usr/include/eigen3/Eigen/src/Core/DenseBase.h +../plugins/BlockMethods.h +/usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + +/usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + +/usr/include/eigen3/Eigen/src/Core/DenseStorage.h + +/usr/include/eigen3/Eigen/src/Core/Diagonal.h + +/usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + +/usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + +/usr/include/eigen3/Eigen/src/Core/Dot.h + +/usr/include/eigen3/Eigen/src/Core/EigenBase.h + +/usr/include/eigen3/Eigen/src/Core/Flagged.h + +/usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + +/usr/include/eigen3/Eigen/src/Core/Functors.h + +/usr/include/eigen3/Eigen/src/Core/Fuzzy.h + +/usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + +/usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + +/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + +/usr/include/eigen3/Eigen/src/Core/IO.h + +/usr/include/eigen3/Eigen/src/Core/Map.h + +/usr/include/eigen3/Eigen/src/Core/MapBase.h + +/usr/include/eigen3/Eigen/src/Core/MathFunctions.h + +/usr/include/eigen3/Eigen/src/Core/Matrix.h + +/usr/include/eigen3/Eigen/src/Core/MatrixBase.h +../plugins/CommonCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +../plugins/CommonCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +../plugins/MatrixCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +../plugins/MatrixCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/Core/NestByValue.h + +/usr/include/eigen3/Eigen/src/Core/NoAlias.h + +/usr/include/eigen3/Eigen/src/Core/NumTraits.h + +/usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + +/usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + +/usr/include/eigen3/Eigen/src/Core/ProductBase.h + +/usr/include/eigen3/Eigen/src/Core/Random.h + +/usr/include/eigen3/Eigen/src/Core/Redux.h + +/usr/include/eigen3/Eigen/src/Core/Ref.h + +/usr/include/eigen3/Eigen/src/Core/Replicate.h + +/usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + +/usr/include/eigen3/Eigen/src/Core/Reverse.h + +/usr/include/eigen3/Eigen/src/Core/Select.h + +/usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + +/usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + +/usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + +/usr/include/eigen3/Eigen/src/Core/StableNorm.h + +/usr/include/eigen3/Eigen/src/Core/Stride.h + +/usr/include/eigen3/Eigen/src/Core/Swap.h + +/usr/include/eigen3/Eigen/src/Core/Transpose.h + +/usr/include/eigen3/Eigen/src/Core/Transpositions.h + +/usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + +/usr/include/eigen3/Eigen/src/Core/VectorBlock.h + +/usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + +/usr/include/eigen3/Eigen/src/Core/Visitor.h + +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + +/usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + +/usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + +/usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + +/usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + +/usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + +/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + +/usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + +/usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + +/usr/include/eigen3/Eigen/src/Core/util/Constants.h + +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + +/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + +/usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +mkl.h +- +mkl_lapacke.h +- + +/usr/include/eigen3/Eigen/src/Core/util/Macros.h +cstdlib +- +iostream +- + +/usr/include/eigen3/Eigen/src/Core/util/Memory.h +unistd.h +- + +/usr/include/eigen3/Eigen/src/Core/util/Meta.h + +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + +/usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +limits +- +RotationBase.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +Rotation2D.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +Quaternion.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +AngleAxis.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +Transform.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +Translation.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +Scaling.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +AlignedBox.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +Hyperplane.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +ParametrizedLine.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +RotationBase.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +Rotation2D.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +Quaternion.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +AngleAxis.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +Transform.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +Translation.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +Scaling.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +AlignedBox.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +Hyperplane.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +ParametrizedLine.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/././HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/././HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +./ComplexSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +./RealSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +./RealQZ.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +./Tridiagonalization.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +./Tridiagonalization.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + +/usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + +/usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + +/usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + +/usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + +/usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + +/usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + +/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + +/usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + +/usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + +/usr/include/eigen3/Eigen/src/Geometry/Scaling.h + +/usr/include/eigen3/Eigen/src/Geometry/Transform.h + +/usr/include/eigen3/Eigen/src/Geometry/Translation.h + +/usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + +/usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + +/usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + +/usr/include/eigen3/Eigen/src/Householder/Householder.h + +/usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + +/usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + +/usr/include/eigen3/Eigen/src/LU/Determinant.h + +/usr/include/eigen3/Eigen/src/LU/FullPivLU.h + +/usr/include/eigen3/Eigen/src/LU/Inverse.h + +/usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + +/usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/LU/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/QR/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + +/usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + +/usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/QR/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/SVD/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + +/usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +Eigen/src/StlSupport/details.h +/usr/include/eigen3/Eigen/src/StlSupport/Eigen/src/StlSupport/details.h + +/usr/include/eigen3/Eigen/src/StlSupport/details.h + +/usr/include/eigen3/Eigen/src/misc/Image.h + +/usr/include/eigen3/Eigen/src/misc/Kernel.h + +/usr/include/eigen3/Eigen/src/misc/Solve.h + +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + +/usr/local/include/opencv/cxcore.h +opencv2/core/core_c.h +/usr/local/include/opencv/opencv2/core/core_c.h + +/usr/local/include/opencv2/calib3d.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/opencv2/features2d.hpp +opencv2/core/affine.hpp +/usr/local/include/opencv2/opencv2/core/affine.hpp +opencv2/calib3d/calib3d_c.h +/usr/local/include/opencv2/opencv2/calib3d/calib3d_c.h + +/usr/local/include/opencv2/calib3d/calib3d.hpp +opencv2/calib3d.hpp +/usr/local/include/opencv2/calib3d/opencv2/calib3d.hpp + +/usr/local/include/opencv2/calib3d/calib3d_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/calib3d/opencv2/core/core_c.h + +/usr/local/include/opencv2/core.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/opencv2/core/cvdef.h +opencv2/core/version.hpp +/usr/local/include/opencv2/opencv2/core/version.hpp +opencv2/core/base.hpp +/usr/local/include/opencv2/opencv2/core/base.hpp +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/opencv2/core/cvstd.hpp +opencv2/core/traits.hpp +/usr/local/include/opencv2/opencv2/core/traits.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/opencv2/core/matx.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/opencv2/core/types.hpp +opencv2/core/mat.hpp +/usr/local/include/opencv2/opencv2/core/mat.hpp +opencv2/core/persistence.hpp +/usr/local/include/opencv2/opencv2/core/persistence.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/opencv2/opencv.hpp +opencv2/xfeatures2d.hpp +/usr/local/include/opencv2/opencv2/xfeatures2d.hpp +opencv2/core/operations.hpp +/usr/local/include/opencv2/opencv2/core/operations.hpp +opencv2/core/cvstd.inl.hpp +/usr/local/include/opencv2/opencv2/core/cvstd.inl.hpp +opencv2/core/utility.hpp +/usr/local/include/opencv2/opencv2/core/utility.hpp +opencv2/core/optim.hpp +/usr/local/include/opencv2/opencv2/core/optim.hpp + +/usr/local/include/opencv2/core/affine.hpp +opencv2/core.hpp +- + +/usr/local/include/opencv2/core/base.hpp +climits +- +algorithm +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/core/opencv2/core/cvstd.hpp +opencv2/core/neon_utils.hpp +/usr/local/include/opencv2/core/opencv2/core/neon_utils.hpp + +/usr/local/include/opencv2/core/bufferpool.hpp + +/usr/local/include/opencv2/core/core.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/core_c.h +opencv2/core/types_c.h +/usr/local/include/opencv2/core/opencv2/core/types_c.h +cxcore.h +/usr/local/include/opencv2/core/cxcore.h +cxcore.h +/usr/local/include/opencv2/core/cxcore.h +opencv2/core/utility.hpp +/usr/local/include/opencv2/core/opencv2/core/utility.hpp + +/usr/local/include/opencv2/core/cvdef.h +limits.h +- +opencv2/core/hal/interface.h +/usr/local/include/opencv2/core/opencv2/core/hal/interface.h +emmintrin.h +- +pmmintrin.h +- +tmmintrin.h +- +smmintrin.h +- +nmmintrin.h +- +nmmintrin.h +- +popcntintrin.h +- +immintrin.h +- +immintrin.h +- +Intrin.h +- +arm_neon.h +/usr/local/include/opencv2/core/arm_neon.h +arm_neon.h +- +intrin.h +- + +/usr/local/include/opencv2/core/cvstd.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +cstddef +- +cstring +- +cctype +- +string +- +algorithm +- +utility +- +cstdlib +- +cmath +- +opencv2/core/ptr.inl.hpp +/usr/local/include/opencv2/core/opencv2/core/ptr.inl.hpp + +/usr/local/include/opencv2/core/cvstd.inl.hpp +complex +- +ostream +- + +/usr/local/include/opencv2/core/fast_math.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +fastmath.h +- +cmath +- +math.h +- +tegra_round.hpp +/usr/local/include/opencv2/core/tegra_round.hpp + +/usr/local/include/opencv2/core/hal/interface.h +cstddef +- +stddef.h +- +cstdint +- +stdint.h +- + +/usr/local/include/opencv2/core/mat.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/core/opencv2/core/matx.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/core/opencv2/core/types.hpp +opencv2/core/bufferpool.hpp +/usr/local/include/opencv2/core/opencv2/core/bufferpool.hpp +opencv2/core/mat.inl.hpp +/usr/local/include/opencv2/core/opencv2/core/mat.inl.hpp + +/usr/local/include/opencv2/core/mat.inl.hpp + +/usr/local/include/opencv2/core/matx.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/base.hpp +/usr/local/include/opencv2/core/opencv2/core/base.hpp +opencv2/core/traits.hpp +/usr/local/include/opencv2/core/opencv2/core/traits.hpp +opencv2/core/saturate.hpp +/usr/local/include/opencv2/core/opencv2/core/saturate.hpp + +/usr/local/include/opencv2/core/neon_utils.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h + +/usr/local/include/opencv2/core/operations.hpp +cstdio +- + +/usr/local/include/opencv2/core/optim.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/persistence.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/core/opencv2/core/types.hpp +opencv2/core/mat.hpp +/usr/local/include/opencv2/core/opencv2/core/mat.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/core/opencv2/opencv.hpp +time.h +- + +/usr/local/include/opencv2/core/ptr.inl.hpp +algorithm +- + +/usr/local/include/opencv2/core/saturate.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/fast_math.hpp +/usr/local/include/opencv2/core/opencv2/core/fast_math.hpp + +/usr/local/include/opencv2/core/traits.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h + +/usr/local/include/opencv2/core/types.hpp +climits +- +cfloat +- +vector +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/core/opencv2/core/cvstd.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/core/opencv2/core/matx.hpp + +/usr/local/include/opencv2/core/types_c.h +ipl.h +- +ipl/ipl.h +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +assert.h +- +stdlib.h +- +string.h +- +float.h +- +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/utility.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp +opencv2/core/core_c.h +/usr/local/include/opencv2/core/opencv2/core/core_c.h + +/usr/local/include/opencv2/core/version.hpp + +/usr/local/include/opencv2/features2d.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/flann/miniflann.hpp +/usr/local/include/opencv2/opencv2/flann/miniflann.hpp + +/usr/local/include/opencv2/features2d/features2d.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/features2d/opencv2/features2d.hpp + +/usr/local/include/opencv2/flann/config.h + +/usr/local/include/opencv2/flann/defines.h +config.h +/usr/local/include/opencv2/flann/config.h + +/usr/local/include/opencv2/flann/miniflann.hpp +opencv2/core.hpp +/usr/local/include/opencv2/flann/opencv2/core.hpp +opencv2/flann/defines.h +/usr/local/include/opencv2/flann/opencv2/flann/defines.h + +/usr/local/include/opencv2/highgui.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgcodecs.hpp +/usr/local/include/opencv2/opencv2/imgcodecs.hpp +opencv2/videoio.hpp +/usr/local/include/opencv2/opencv2/videoio.hpp +opencv2/highgui/highgui_c.h +/usr/local/include/opencv2/opencv2/highgui/highgui_c.h + +/usr/local/include/opencv2/highgui/highgui.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/highgui/opencv2/highgui.hpp + +/usr/local/include/opencv2/highgui/highgui_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/highgui/opencv2/core/core_c.h +opencv2/imgproc/imgproc_c.h +/usr/local/include/opencv2/highgui/opencv2/imgproc/imgproc_c.h +opencv2/imgcodecs/imgcodecs_c.h +/usr/local/include/opencv2/highgui/opencv2/imgcodecs/imgcodecs_c.h +opencv2/videoio/videoio_c.h +/usr/local/include/opencv2/highgui/opencv2/videoio/videoio_c.h + +/usr/local/include/opencv2/imgcodecs.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/opencv.hpp +- + +/usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/imgcodecs/opencv2/core/core_c.h + +/usr/local/include/opencv2/imgproc.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/core.hpp +- +opencv2/imgproc.hpp +- +opencv2/imgcodecs.hpp +- +opencv2/highgui.hpp +- +iostream +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +math.h +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/opencv2/highgui.hpp +opencv2/imgproc/imgproc_c.h +/usr/local/include/opencv2/opencv2/imgproc/imgproc_c.h + +/usr/local/include/opencv2/imgproc/imgproc.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/imgproc/opencv2/imgproc.hpp + +/usr/local/include/opencv2/imgproc/imgproc_c.h +opencv2/imgproc/types_c.h +/usr/local/include/opencv2/imgproc/opencv2/imgproc/types_c.h + +/usr/local/include/opencv2/imgproc/types_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/imgproc/opencv2/core/core_c.h + +/usr/local/include/opencv2/ml.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +float.h +- +map +- +iostream +- + +/usr/local/include/opencv2/objdetect.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/objdetect/detection_based_tracker.hpp +/usr/local/include/opencv2/opencv2/objdetect/detection_based_tracker.hpp +opencv2/objdetect/objdetect_c.h +/usr/local/include/opencv2/opencv2/objdetect/objdetect_c.h + +/usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +vector +- + +/usr/local/include/opencv2/objdetect/objdetect_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/objdetect/opencv2/core/core_c.h +deque +- +vector +- + +/usr/local/include/opencv2/opencv.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/photo.hpp +/usr/local/include/opencv2/opencv2/photo.hpp +opencv2/video.hpp +/usr/local/include/opencv2/opencv2/video.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/opencv2/features2d.hpp +opencv2/objdetect.hpp +/usr/local/include/opencv2/opencv2/objdetect.hpp +opencv2/calib3d.hpp +/usr/local/include/opencv2/opencv2/calib3d.hpp +opencv2/imgcodecs.hpp +/usr/local/include/opencv2/opencv2/imgcodecs.hpp +opencv2/videoio.hpp +/usr/local/include/opencv2/opencv2/videoio.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/opencv2/highgui.hpp +opencv2/ml.hpp +/usr/local/include/opencv2/opencv2/ml.hpp + +/usr/local/include/opencv2/photo.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/photo/photo_c.h +/usr/local/include/opencv2/opencv2/photo/photo_c.h + +/usr/local/include/opencv2/photo/photo_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/photo/opencv2/core/core_c.h + +/usr/local/include/opencv2/video.hpp +opencv2/video/tracking.hpp +/usr/local/include/opencv2/opencv2/video/tracking.hpp +opencv2/video/background_segm.hpp +/usr/local/include/opencv2/opencv2/video/background_segm.hpp +opencv2/video/tracking_c.h +/usr/local/include/opencv2/opencv2/video/tracking_c.h + +/usr/local/include/opencv2/video/background_segm.hpp +opencv2/core.hpp +/usr/local/include/opencv2/video/opencv2/core.hpp + +/usr/local/include/opencv2/video/tracking.hpp +opencv2/core.hpp +/usr/local/include/opencv2/video/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/video/opencv2/imgproc.hpp + +/usr/local/include/opencv2/video/tracking_c.h +opencv2/imgproc/types_c.h +/usr/local/include/opencv2/video/opencv2/imgproc/types_c.h + +/usr/local/include/opencv2/videoio.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/opencv2/opencv.hpp + +/usr/local/include/opencv2/videoio/videoio_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/videoio/opencv2/core/core_c.h + diff --git a/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/DependInfo.cmake b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/DependInfo.cmake new file mode 100644 index 00000000..bc175aab --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/DependInfo.cmake @@ -0,0 +1,30 @@ +# The set of languages for which implicit dependencies are needed: +SET(CMAKE_DEPENDS_LANGUAGES + "CXX" + ) +# The set of files for implicit dependencies of each language: +SET(CMAKE_DEPENDS_CHECK_CXX + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/camera.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/camera.cpp.o" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/config.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/config.cpp.o" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/frame.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/frame.cpp.o" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/map.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/map.cpp.o" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/mappoint.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/mappoint.cpp.o" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/visual_odometry.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/visual_odometry.cpp.o" + ) +SET(CMAKE_CXX_COMPILER_ID "GNU") + +# Targets to which this target links. +SET(CMAKE_TARGET_LINKED_INFO_FILES + ) + +# The include file search paths: +SET(CMAKE_C_TARGET_INCLUDE_PATH + "/usr/include/eigen3" + "/usr/local/include/opencv" + "/usr/local/include" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus" + "../include" + ) +SET(CMAKE_CXX_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) +SET(CMAKE_Fortran_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) +SET(CMAKE_ASM_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) diff --git a/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/build.make b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/build.make new file mode 100644 index 00000000..beac4fe4 --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/build.make @@ -0,0 +1,259 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2" + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" + +# Include any dependencies generated for this target. +include src/CMakeFiles/myslam.dir/depend.make + +# Include the progress variables for this target. +include src/CMakeFiles/myslam.dir/progress.make + +# Include the compile flags for this target's objects. +include src/CMakeFiles/myslam.dir/flags.make + +src/CMakeFiles/myslam.dir/frame.cpp.o: src/CMakeFiles/myslam.dir/flags.make +src/CMakeFiles/myslam.dir/frame.cpp.o: ../src/frame.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles" $(CMAKE_PROGRESS_1) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object src/CMakeFiles/myslam.dir/frame.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/myslam.dir/frame.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/frame.cpp" + +src/CMakeFiles/myslam.dir/frame.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/myslam.dir/frame.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/frame.cpp" > CMakeFiles/myslam.dir/frame.cpp.i + +src/CMakeFiles/myslam.dir/frame.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/myslam.dir/frame.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/frame.cpp" -o CMakeFiles/myslam.dir/frame.cpp.s + +src/CMakeFiles/myslam.dir/frame.cpp.o.requires: +.PHONY : src/CMakeFiles/myslam.dir/frame.cpp.o.requires + +src/CMakeFiles/myslam.dir/frame.cpp.o.provides: src/CMakeFiles/myslam.dir/frame.cpp.o.requires + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/frame.cpp.o.provides.build +.PHONY : src/CMakeFiles/myslam.dir/frame.cpp.o.provides + +src/CMakeFiles/myslam.dir/frame.cpp.o.provides.build: src/CMakeFiles/myslam.dir/frame.cpp.o + +src/CMakeFiles/myslam.dir/mappoint.cpp.o: src/CMakeFiles/myslam.dir/flags.make +src/CMakeFiles/myslam.dir/mappoint.cpp.o: ../src/mappoint.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles" $(CMAKE_PROGRESS_2) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object src/CMakeFiles/myslam.dir/mappoint.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/myslam.dir/mappoint.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/mappoint.cpp" + +src/CMakeFiles/myslam.dir/mappoint.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/myslam.dir/mappoint.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/mappoint.cpp" > CMakeFiles/myslam.dir/mappoint.cpp.i + +src/CMakeFiles/myslam.dir/mappoint.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/myslam.dir/mappoint.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/mappoint.cpp" -o CMakeFiles/myslam.dir/mappoint.cpp.s + +src/CMakeFiles/myslam.dir/mappoint.cpp.o.requires: +.PHONY : src/CMakeFiles/myslam.dir/mappoint.cpp.o.requires + +src/CMakeFiles/myslam.dir/mappoint.cpp.o.provides: src/CMakeFiles/myslam.dir/mappoint.cpp.o.requires + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/mappoint.cpp.o.provides.build +.PHONY : src/CMakeFiles/myslam.dir/mappoint.cpp.o.provides + +src/CMakeFiles/myslam.dir/mappoint.cpp.o.provides.build: src/CMakeFiles/myslam.dir/mappoint.cpp.o + +src/CMakeFiles/myslam.dir/map.cpp.o: src/CMakeFiles/myslam.dir/flags.make +src/CMakeFiles/myslam.dir/map.cpp.o: ../src/map.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles" $(CMAKE_PROGRESS_3) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object src/CMakeFiles/myslam.dir/map.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/myslam.dir/map.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/map.cpp" + +src/CMakeFiles/myslam.dir/map.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/myslam.dir/map.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/map.cpp" > CMakeFiles/myslam.dir/map.cpp.i + +src/CMakeFiles/myslam.dir/map.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/myslam.dir/map.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/map.cpp" -o CMakeFiles/myslam.dir/map.cpp.s + +src/CMakeFiles/myslam.dir/map.cpp.o.requires: +.PHONY : src/CMakeFiles/myslam.dir/map.cpp.o.requires + +src/CMakeFiles/myslam.dir/map.cpp.o.provides: src/CMakeFiles/myslam.dir/map.cpp.o.requires + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/map.cpp.o.provides.build +.PHONY : src/CMakeFiles/myslam.dir/map.cpp.o.provides + +src/CMakeFiles/myslam.dir/map.cpp.o.provides.build: src/CMakeFiles/myslam.dir/map.cpp.o + +src/CMakeFiles/myslam.dir/camera.cpp.o: src/CMakeFiles/myslam.dir/flags.make +src/CMakeFiles/myslam.dir/camera.cpp.o: ../src/camera.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles" $(CMAKE_PROGRESS_4) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object src/CMakeFiles/myslam.dir/camera.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/myslam.dir/camera.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/camera.cpp" + +src/CMakeFiles/myslam.dir/camera.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/myslam.dir/camera.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/camera.cpp" > CMakeFiles/myslam.dir/camera.cpp.i + +src/CMakeFiles/myslam.dir/camera.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/myslam.dir/camera.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/camera.cpp" -o CMakeFiles/myslam.dir/camera.cpp.s + +src/CMakeFiles/myslam.dir/camera.cpp.o.requires: +.PHONY : src/CMakeFiles/myslam.dir/camera.cpp.o.requires + +src/CMakeFiles/myslam.dir/camera.cpp.o.provides: src/CMakeFiles/myslam.dir/camera.cpp.o.requires + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/camera.cpp.o.provides.build +.PHONY : src/CMakeFiles/myslam.dir/camera.cpp.o.provides + +src/CMakeFiles/myslam.dir/camera.cpp.o.provides.build: src/CMakeFiles/myslam.dir/camera.cpp.o + +src/CMakeFiles/myslam.dir/config.cpp.o: src/CMakeFiles/myslam.dir/flags.make +src/CMakeFiles/myslam.dir/config.cpp.o: ../src/config.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles" $(CMAKE_PROGRESS_5) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object src/CMakeFiles/myslam.dir/config.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/myslam.dir/config.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/config.cpp" + +src/CMakeFiles/myslam.dir/config.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/myslam.dir/config.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/config.cpp" > CMakeFiles/myslam.dir/config.cpp.i + +src/CMakeFiles/myslam.dir/config.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/myslam.dir/config.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/config.cpp" -o CMakeFiles/myslam.dir/config.cpp.s + +src/CMakeFiles/myslam.dir/config.cpp.o.requires: +.PHONY : src/CMakeFiles/myslam.dir/config.cpp.o.requires + +src/CMakeFiles/myslam.dir/config.cpp.o.provides: src/CMakeFiles/myslam.dir/config.cpp.o.requires + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/config.cpp.o.provides.build +.PHONY : src/CMakeFiles/myslam.dir/config.cpp.o.provides + +src/CMakeFiles/myslam.dir/config.cpp.o.provides.build: src/CMakeFiles/myslam.dir/config.cpp.o + +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: src/CMakeFiles/myslam.dir/flags.make +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../src/visual_odometry.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles" $(CMAKE_PROGRESS_6) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object src/CMakeFiles/myslam.dir/visual_odometry.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/myslam.dir/visual_odometry.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/visual_odometry.cpp" + +src/CMakeFiles/myslam.dir/visual_odometry.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/myslam.dir/visual_odometry.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/visual_odometry.cpp" > CMakeFiles/myslam.dir/visual_odometry.cpp.i + +src/CMakeFiles/myslam.dir/visual_odometry.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/myslam.dir/visual_odometry.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/visual_odometry.cpp" -o CMakeFiles/myslam.dir/visual_odometry.cpp.s + +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o.requires: +.PHONY : src/CMakeFiles/myslam.dir/visual_odometry.cpp.o.requires + +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o.provides: src/CMakeFiles/myslam.dir/visual_odometry.cpp.o.requires + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/visual_odometry.cpp.o.provides.build +.PHONY : src/CMakeFiles/myslam.dir/visual_odometry.cpp.o.provides + +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o.provides.build: src/CMakeFiles/myslam.dir/visual_odometry.cpp.o + +# Object files for target myslam +myslam_OBJECTS = \ +"CMakeFiles/myslam.dir/frame.cpp.o" \ +"CMakeFiles/myslam.dir/mappoint.cpp.o" \ +"CMakeFiles/myslam.dir/map.cpp.o" \ +"CMakeFiles/myslam.dir/camera.cpp.o" \ +"CMakeFiles/myslam.dir/config.cpp.o" \ +"CMakeFiles/myslam.dir/visual_odometry.cpp.o" + +# External object files for target myslam +myslam_EXTERNAL_OBJECTS = + +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/frame.cpp.o +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/mappoint.cpp.o +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/map.cpp.o +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/camera.cpp.o +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/config.cpp.o +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/visual_odometry.cpp.o +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/build.make +../lib/libmyslam.so: /usr/local/lib/libopencv_viz.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_videostab.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_videoio.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_video.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_superres.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_stitching.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_shape.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_photo.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_objdetect.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_ml.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_imgproc.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_imgcodecs.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_highgui.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_flann.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_features2d.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_core.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_calib3d.so.3.1.0 +../lib/libmyslam.so: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build/libSophus.so +../lib/libmyslam.so: /usr/local/lib/libopencv_features2d.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_ml.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_highgui.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_videoio.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_imgcodecs.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_flann.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_video.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_imgproc.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_core.so.3.1.0 +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/link.txt + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --red --bold "Linking CXX shared library ../../lib/libmyslam.so" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src" && $(CMAKE_COMMAND) -E cmake_link_script CMakeFiles/myslam.dir/link.txt --verbose=$(VERBOSE) + +# Rule to build all files generated by this target. +src/CMakeFiles/myslam.dir/build: ../lib/libmyslam.so +.PHONY : src/CMakeFiles/myslam.dir/build + +src/CMakeFiles/myslam.dir/requires: src/CMakeFiles/myslam.dir/frame.cpp.o.requires +src/CMakeFiles/myslam.dir/requires: src/CMakeFiles/myslam.dir/mappoint.cpp.o.requires +src/CMakeFiles/myslam.dir/requires: src/CMakeFiles/myslam.dir/map.cpp.o.requires +src/CMakeFiles/myslam.dir/requires: src/CMakeFiles/myslam.dir/camera.cpp.o.requires +src/CMakeFiles/myslam.dir/requires: src/CMakeFiles/myslam.dir/config.cpp.o.requires +src/CMakeFiles/myslam.dir/requires: src/CMakeFiles/myslam.dir/visual_odometry.cpp.o.requires +.PHONY : src/CMakeFiles/myslam.dir/requires + +src/CMakeFiles/myslam.dir/clean: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src" && $(CMAKE_COMMAND) -P CMakeFiles/myslam.dir/cmake_clean.cmake +.PHONY : src/CMakeFiles/myslam.dir/clean + +src/CMakeFiles/myslam.dir/depend: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/DependInfo.cmake" --color=$(COLOR) +.PHONY : src/CMakeFiles/myslam.dir/depend + diff --git a/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/camera.cpp.o b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/camera.cpp.o new file mode 100644 index 00000000..844b6ddf Binary files /dev/null and b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/camera.cpp.o differ diff --git a/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/cmake_clean.cmake b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/cmake_clean.cmake new file mode 100644 index 00000000..9881e019 --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/cmake_clean.cmake @@ -0,0 +1,15 @@ +FILE(REMOVE_RECURSE + "CMakeFiles/myslam.dir/frame.cpp.o" + "CMakeFiles/myslam.dir/mappoint.cpp.o" + "CMakeFiles/myslam.dir/map.cpp.o" + "CMakeFiles/myslam.dir/camera.cpp.o" + "CMakeFiles/myslam.dir/config.cpp.o" + "CMakeFiles/myslam.dir/visual_odometry.cpp.o" + "../../lib/libmyslam.pdb" + "../../lib/libmyslam.so" +) + +# Per-language clean rules from dependency scanning. +FOREACH(lang CXX) + INCLUDE(CMakeFiles/myslam.dir/cmake_clean_${lang}.cmake OPTIONAL) +ENDFOREACH(lang) diff --git a/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/config.cpp.o b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/config.cpp.o new file mode 100644 index 00000000..efc49619 Binary files /dev/null and b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/config.cpp.o differ diff --git a/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/depend.internal b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/depend.internal new file mode 100644 index 00000000..49e65b93 --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/depend.internal @@ -0,0 +1,1589 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +src/CMakeFiles/myslam.dir/camera.cpp.o + ../include/myslam/camera.h + ../include/myslam/common_include.h + ../include/myslam/config.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/camera.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h +src/CMakeFiles/myslam.dir/config.cpp.o + ../include/myslam/common_include.h + ../include/myslam/config.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/config.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o + ../include/myslam/camera.h + ../include/myslam/common_include.h + ../include/myslam/frame.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/frame.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h +src/CMakeFiles/myslam.dir/map.cpp.o + ../include/myslam/camera.h + ../include/myslam/common_include.h + ../include/myslam/frame.h + ../include/myslam/map.h + ../include/myslam/mappoint.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/map.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o + ../include/myslam/common_include.h + ../include/myslam/mappoint.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/mappoint.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o + ../include/myslam/camera.h + ../include/myslam/common_include.h + ../include/myslam/config.h + ../include/myslam/frame.h + ../include/myslam/map.h + ../include/myslam/mappoint.h + ../include/myslam/visual_odometry.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src/visual_odometry.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/features2d/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h diff --git a/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/depend.make b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/depend.make new file mode 100644 index 00000000..e4f668ce --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/depend.make @@ -0,0 +1,1589 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +src/CMakeFiles/myslam.dir/camera.cpp.o: ../include/myslam/camera.h +src/CMakeFiles/myslam.dir/camera.cpp.o: ../include/myslam/common_include.h +src/CMakeFiles/myslam.dir/camera.cpp.o: ../include/myslam/config.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +src/CMakeFiles/myslam.dir/camera.cpp.o: ../src/camera.cpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Cholesky +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Core +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Geometry +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Householder +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Jacobi +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/LU +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/QR +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/SVD +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/StdVector +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv/cxcore.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/calib3d.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/affine.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/base.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/core.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/core_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/cvdef.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/mat.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/matx.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/operations.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/optim.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/traits.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/types.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/types_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/utility.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/version.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/features2d.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/flann/config.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/flann/defines.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/highgui.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/imgproc.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/ml.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/objdetect.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/opencv.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/photo.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/video.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/videoio.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + +src/CMakeFiles/myslam.dir/config.cpp.o: ../include/myslam/common_include.h +src/CMakeFiles/myslam.dir/config.cpp.o: ../include/myslam/config.h +src/CMakeFiles/myslam.dir/config.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +src/CMakeFiles/myslam.dir/config.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +src/CMakeFiles/myslam.dir/config.cpp.o: ../src/config.cpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Cholesky +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Core +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Geometry +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Householder +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Jacobi +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/LU +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/QR +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/SVD +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/StdVector +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv/cxcore.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/calib3d.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/affine.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/base.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/core.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/core_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/cvdef.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/mat.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/matx.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/operations.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/optim.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/traits.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/types.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/types_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/utility.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/version.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/features2d.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/flann/config.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/flann/defines.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/highgui.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/imgproc.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/ml.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/objdetect.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/opencv.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/photo.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/video.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/videoio.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + +src/CMakeFiles/myslam.dir/frame.cpp.o: ../include/myslam/camera.h +src/CMakeFiles/myslam.dir/frame.cpp.o: ../include/myslam/common_include.h +src/CMakeFiles/myslam.dir/frame.cpp.o: ../include/myslam/frame.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +src/CMakeFiles/myslam.dir/frame.cpp.o: ../src/frame.cpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Cholesky +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Core +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Geometry +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Householder +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Jacobi +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/LU +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/QR +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/SVD +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/StdVector +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv/cxcore.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/calib3d.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/affine.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/base.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/core.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/core_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/cvdef.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/mat.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/matx.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/operations.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/optim.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/traits.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/types.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/types_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/utility.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/version.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/features2d.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/flann/config.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/flann/defines.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/highgui.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/imgproc.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/ml.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/objdetect.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/opencv.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/photo.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/video.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/videoio.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + +src/CMakeFiles/myslam.dir/map.cpp.o: ../include/myslam/camera.h +src/CMakeFiles/myslam.dir/map.cpp.o: ../include/myslam/common_include.h +src/CMakeFiles/myslam.dir/map.cpp.o: ../include/myslam/frame.h +src/CMakeFiles/myslam.dir/map.cpp.o: ../include/myslam/map.h +src/CMakeFiles/myslam.dir/map.cpp.o: ../include/myslam/mappoint.h +src/CMakeFiles/myslam.dir/map.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +src/CMakeFiles/myslam.dir/map.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +src/CMakeFiles/myslam.dir/map.cpp.o: ../src/map.cpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Cholesky +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Core +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Geometry +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Householder +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Jacobi +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/LU +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/QR +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/SVD +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/StdVector +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv/cxcore.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/calib3d.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/affine.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/base.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/core.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/core_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/cvdef.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/mat.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/matx.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/operations.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/optim.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/traits.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/types.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/types_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/utility.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/version.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/features2d.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/flann/config.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/flann/defines.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/highgui.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/imgproc.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/ml.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/objdetect.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/opencv.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/photo.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/video.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/videoio.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + +src/CMakeFiles/myslam.dir/mappoint.cpp.o: ../include/myslam/common_include.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: ../include/myslam/mappoint.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: ../src/mappoint.cpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Cholesky +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Core +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Geometry +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Householder +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Jacobi +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/LU +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/QR +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/SVD +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/StdVector +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv/cxcore.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/calib3d.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/affine.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/base.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/core.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/core_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/cvdef.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/mat.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/matx.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/operations.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/optim.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/traits.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/types.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/types_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/utility.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/version.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/features2d.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/flann/config.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/flann/defines.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/highgui.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/imgproc.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/ml.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/objdetect.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/opencv.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/photo.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/video.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/videoio.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../include/myslam/camera.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../include/myslam/common_include.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../include/myslam/config.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../include/myslam/frame.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../include/myslam/map.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../include/myslam/mappoint.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../include/myslam/visual_odometry.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../src/visual_odometry.cpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/Cholesky +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/Core +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/Geometry +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/Householder +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/Jacobi +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/LU +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/QR +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/SVD +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/StdVector +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv/cxcore.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/calib3d.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/calib3d/calib3d.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/affine.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/base.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/core.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/core_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/cvdef.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/mat.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/matx.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/operations.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/optim.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/traits.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/types.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/types_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/utility.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/version.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/features2d.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/features2d/features2d.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/flann/config.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/flann/defines.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/highgui.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/highgui/highgui.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/imgproc.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/imgproc/imgproc.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/ml.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/objdetect.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/opencv.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/photo.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/video.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/videoio.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + diff --git a/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/flags.make b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/flags.make new file mode 100644 index 00000000..1da6fca9 --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/flags.make @@ -0,0 +1,8 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# compile CXX with g++ +CXX_FLAGS = -std=c++11 -march=native -O3 -O3 -DNDEBUG -fPIC -I/usr/include/eigen3 -I/usr/local/include/opencv -I/usr/local/include -I/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus -I"/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/include" + +CXX_DEFINES = -Dmyslam_EXPORTS + diff --git a/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/frame.cpp.o b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/frame.cpp.o new file mode 100644 index 00000000..588f9de5 Binary files /dev/null and b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/frame.cpp.o differ diff --git a/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/link.txt b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/link.txt new file mode 100644 index 00000000..00ad7b82 --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/link.txt @@ -0,0 +1 @@ +g++ -fPIC -std=c++11 -march=native -O3 -O3 -DNDEBUG -shared -Wl,-soname,libmyslam.so -o ../../lib/libmyslam.so CMakeFiles/myslam.dir/frame.cpp.o CMakeFiles/myslam.dir/mappoint.cpp.o CMakeFiles/myslam.dir/map.cpp.o CMakeFiles/myslam.dir/camera.cpp.o CMakeFiles/myslam.dir/config.cpp.o CMakeFiles/myslam.dir/visual_odometry.cpp.o /usr/local/lib/libopencv_viz.so.3.1.0 /usr/local/lib/libopencv_videostab.so.3.1.0 /usr/local/lib/libopencv_videoio.so.3.1.0 /usr/local/lib/libopencv_video.so.3.1.0 /usr/local/lib/libopencv_superres.so.3.1.0 /usr/local/lib/libopencv_stitching.so.3.1.0 /usr/local/lib/libopencv_shape.so.3.1.0 /usr/local/lib/libopencv_photo.so.3.1.0 /usr/local/lib/libopencv_objdetect.so.3.1.0 /usr/local/lib/libopencv_ml.so.3.1.0 /usr/local/lib/libopencv_imgproc.so.3.1.0 /usr/local/lib/libopencv_imgcodecs.so.3.1.0 /usr/local/lib/libopencv_highgui.so.3.1.0 /usr/local/lib/libopencv_flann.so.3.1.0 /usr/local/lib/libopencv_features2d.so.3.1.0 /usr/local/lib/libopencv_core.so.3.1.0 /usr/local/lib/libopencv_calib3d.so.3.1.0 /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build/libSophus.so -lg2o_core -lg2o_stuff -lg2o_types_sba /usr/local/lib/libopencv_features2d.so.3.1.0 /usr/local/lib/libopencv_ml.so.3.1.0 /usr/local/lib/libopencv_highgui.so.3.1.0 /usr/local/lib/libopencv_videoio.so.3.1.0 /usr/local/lib/libopencv_imgcodecs.so.3.1.0 /usr/local/lib/libopencv_flann.so.3.1.0 /usr/local/lib/libopencv_video.so.3.1.0 /usr/local/lib/libopencv_imgproc.so.3.1.0 /usr/local/lib/libopencv_core.so.3.1.0 -Wl,-rpath,/usr/local/lib:/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build diff --git a/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/map.cpp.o b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/map.cpp.o new file mode 100644 index 00000000..c19116e7 Binary files /dev/null and b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/map.cpp.o differ diff --git a/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/mappoint.cpp.o b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/mappoint.cpp.o new file mode 100644 index 00000000..082690fc Binary files /dev/null and b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/mappoint.cpp.o differ diff --git a/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/progress.make b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/progress.make new file mode 100644 index 00000000..daba7fae --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/progress.make @@ -0,0 +1,7 @@ +CMAKE_PROGRESS_1 = 1 +CMAKE_PROGRESS_2 = 2 +CMAKE_PROGRESS_3 = 3 +CMAKE_PROGRESS_4 = 4 +CMAKE_PROGRESS_5 = 5 +CMAKE_PROGRESS_6 = 6 + diff --git a/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/visual_odometry.cpp.o b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/visual_odometry.cpp.o new file mode 100644 index 00000000..6e688c6c Binary files /dev/null and b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/visual_odometry.cpp.o differ diff --git a/vSLAM/ch9 project/0.2/build/src/CMakeFiles/progress.marks b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/progress.marks new file mode 100644 index 00000000..1e8b3149 --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/src/CMakeFiles/progress.marks @@ -0,0 +1 @@ +6 diff --git a/vSLAM/ch9 project/0.2/build/src/Makefile b/vSLAM/ch9 project/0.2/build/src/Makefile new file mode 100644 index 00000000..a2c7d4cd --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/src/Makefile @@ -0,0 +1,299 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Default target executed when no arguments are given to make. +default_target: all +.PHONY : default_target + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2" + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" + +#============================================================================= +# Targets provided globally by CMake. + +# Special rule for the target edit_cache +edit_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running interactive CMake command-line interface..." + /usr/bin/cmake -i . +.PHONY : edit_cache + +# Special rule for the target edit_cache +edit_cache/fast: edit_cache +.PHONY : edit_cache/fast + +# Special rule for the target rebuild_cache +rebuild_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake to regenerate build system..." + /usr/bin/cmake -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) +.PHONY : rebuild_cache + +# Special rule for the target rebuild_cache +rebuild_cache/fast: rebuild_cache +.PHONY : rebuild_cache/fast + +# The main all target +all: cmake_check_build_system + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src/CMakeFiles/progress.marks" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f CMakeFiles/Makefile2 src/all + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles" 0 +.PHONY : all + +# The main clean target +clean: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f CMakeFiles/Makefile2 src/clean +.PHONY : clean + +# The main clean target +clean/fast: clean +.PHONY : clean/fast + +# Prepare targets for installation. +preinstall: all + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f CMakeFiles/Makefile2 src/preinstall +.PHONY : preinstall + +# Prepare targets for installation. +preinstall/fast: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f CMakeFiles/Makefile2 src/preinstall +.PHONY : preinstall/fast + +# clear depends +depend: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 1 +.PHONY : depend + +# Convenience name for target. +src/CMakeFiles/myslam.dir/rule: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f CMakeFiles/Makefile2 src/CMakeFiles/myslam.dir/rule +.PHONY : src/CMakeFiles/myslam.dir/rule + +# Convenience name for target. +myslam: src/CMakeFiles/myslam.dir/rule +.PHONY : myslam + +# fast build rule for target. +myslam/fast: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/build +.PHONY : myslam/fast + +camera.o: camera.cpp.o +.PHONY : camera.o + +# target to build an object file +camera.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/camera.cpp.o +.PHONY : camera.cpp.o + +camera.i: camera.cpp.i +.PHONY : camera.i + +# target to preprocess a source file +camera.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/camera.cpp.i +.PHONY : camera.cpp.i + +camera.s: camera.cpp.s +.PHONY : camera.s + +# target to generate assembly for a file +camera.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/camera.cpp.s +.PHONY : camera.cpp.s + +config.o: config.cpp.o +.PHONY : config.o + +# target to build an object file +config.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/config.cpp.o +.PHONY : config.cpp.o + +config.i: config.cpp.i +.PHONY : config.i + +# target to preprocess a source file +config.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/config.cpp.i +.PHONY : config.cpp.i + +config.s: config.cpp.s +.PHONY : config.s + +# target to generate assembly for a file +config.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/config.cpp.s +.PHONY : config.cpp.s + +frame.o: frame.cpp.o +.PHONY : frame.o + +# target to build an object file +frame.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/frame.cpp.o +.PHONY : frame.cpp.o + +frame.i: frame.cpp.i +.PHONY : frame.i + +# target to preprocess a source file +frame.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/frame.cpp.i +.PHONY : frame.cpp.i + +frame.s: frame.cpp.s +.PHONY : frame.s + +# target to generate assembly for a file +frame.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/frame.cpp.s +.PHONY : frame.cpp.s + +map.o: map.cpp.o +.PHONY : map.o + +# target to build an object file +map.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/map.cpp.o +.PHONY : map.cpp.o + +map.i: map.cpp.i +.PHONY : map.i + +# target to preprocess a source file +map.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/map.cpp.i +.PHONY : map.cpp.i + +map.s: map.cpp.s +.PHONY : map.s + +# target to generate assembly for a file +map.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/map.cpp.s +.PHONY : map.cpp.s + +mappoint.o: mappoint.cpp.o +.PHONY : mappoint.o + +# target to build an object file +mappoint.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/mappoint.cpp.o +.PHONY : mappoint.cpp.o + +mappoint.i: mappoint.cpp.i +.PHONY : mappoint.i + +# target to preprocess a source file +mappoint.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/mappoint.cpp.i +.PHONY : mappoint.cpp.i + +mappoint.s: mappoint.cpp.s +.PHONY : mappoint.s + +# target to generate assembly for a file +mappoint.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/mappoint.cpp.s +.PHONY : mappoint.cpp.s + +visual_odometry.o: visual_odometry.cpp.o +.PHONY : visual_odometry.o + +# target to build an object file +visual_odometry.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/visual_odometry.cpp.o +.PHONY : visual_odometry.cpp.o + +visual_odometry.i: visual_odometry.cpp.i +.PHONY : visual_odometry.i + +# target to preprocess a source file +visual_odometry.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/visual_odometry.cpp.i +.PHONY : visual_odometry.cpp.i + +visual_odometry.s: visual_odometry.cpp.s +.PHONY : visual_odometry.s + +# target to generate assembly for a file +visual_odometry.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/visual_odometry.cpp.s +.PHONY : visual_odometry.cpp.s + +# Help Target +help: + @echo "The following are some of the valid targets for this Makefile:" + @echo "... all (the default if no target is provided)" + @echo "... clean" + @echo "... depend" + @echo "... edit_cache" + @echo "... myslam" + @echo "... rebuild_cache" + @echo "... camera.o" + @echo "... camera.i" + @echo "... camera.s" + @echo "... config.o" + @echo "... config.i" + @echo "... config.s" + @echo "... frame.o" + @echo "... frame.i" + @echo "... frame.s" + @echo "... map.o" + @echo "... map.i" + @echo "... map.s" + @echo "... mappoint.o" + @echo "... mappoint.i" + @echo "... mappoint.s" + @echo "... visual_odometry.o" + @echo "... visual_odometry.i" + @echo "... visual_odometry.s" +.PHONY : help + + + +#============================================================================= +# Special targets to cleanup operation of make. + +# Special rule to run CMake to check the build system integrity. +# No rule that depends on this can have commands that come from listfiles +# because they might be regenerated. +cmake_check_build_system: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0 +.PHONY : cmake_check_build_system + diff --git a/vSLAM/ch9 project/0.2/build/src/cmake_install.cmake b/vSLAM/ch9 project/0.2/build/src/cmake_install.cmake new file mode 100644 index 00000000..f8ca4f46 --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/src/cmake_install.cmake @@ -0,0 +1,34 @@ +# Install script for directory: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/src + +# Set the install prefix +IF(NOT DEFINED CMAKE_INSTALL_PREFIX) + SET(CMAKE_INSTALL_PREFIX "/usr/local") +ENDIF(NOT DEFINED CMAKE_INSTALL_PREFIX) +STRING(REGEX REPLACE "/$" "" CMAKE_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}") + +# Set the install configuration name. +IF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + IF(BUILD_TYPE) + STRING(REGEX REPLACE "^[^A-Za-z0-9_]+" "" + CMAKE_INSTALL_CONFIG_NAME "${BUILD_TYPE}") + ELSE(BUILD_TYPE) + SET(CMAKE_INSTALL_CONFIG_NAME "Release") + ENDIF(BUILD_TYPE) + MESSAGE(STATUS "Install configuration: \"${CMAKE_INSTALL_CONFIG_NAME}\"") +ENDIF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + +# Set the component getting installed. +IF(NOT CMAKE_INSTALL_COMPONENT) + IF(COMPONENT) + MESSAGE(STATUS "Install component: \"${COMPONENT}\"") + SET(CMAKE_INSTALL_COMPONENT "${COMPONENT}") + ELSE(COMPONENT) + SET(CMAKE_INSTALL_COMPONENT) + ENDIF(COMPONENT) +ENDIF(NOT CMAKE_INSTALL_COMPONENT) + +# Install shared libraries without execute permission? +IF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + SET(CMAKE_INSTALL_SO_NO_EXE "1") +ENDIF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + diff --git a/vSLAM/ch9 project/0.2/build/test/CMakeFiles/CMakeDirectoryInformation.cmake b/vSLAM/ch9 project/0.2/build/test/CMakeFiles/CMakeDirectoryInformation.cmake new file mode 100644 index 00000000..29e5b04a --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/test/CMakeFiles/CMakeDirectoryInformation.cmake @@ -0,0 +1,16 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Relative path conversion top directories. +SET(CMAKE_RELATIVE_PATH_TOP_SOURCE "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2") +SET(CMAKE_RELATIVE_PATH_TOP_BINARY "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build") + +# Force unix paths in dependencies. +SET(CMAKE_FORCE_UNIX_PATHS 1) + + +# The C and CXX include file regular expressions for this directory. +SET(CMAKE_C_INCLUDE_REGEX_SCAN "^.*$") +SET(CMAKE_C_INCLUDE_REGEX_COMPLAIN "^$") +SET(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN}) +SET(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN}) diff --git a/vSLAM/ch9 project/0.2/build/test/CMakeFiles/progress.marks b/vSLAM/ch9 project/0.2/build/test/CMakeFiles/progress.marks new file mode 100644 index 00000000..7f8f011e --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/test/CMakeFiles/progress.marks @@ -0,0 +1 @@ +7 diff --git a/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/CXX.includecache b/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/CXX.includecache new file mode 100644 index 00000000..8b7d0935 --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/CXX.includecache @@ -0,0 +1,1600 @@ +#IncludeRegexLine: ^[ ]*#[ ]*(include|import)[ ]*[<"]([^">]+)([">]) + +#IncludeRegexScan: ^.*$ + +#IncludeRegexComplain: ^$ + +#IncludeRegexTransform: + +../include/myslam/camera.h +myslam/common_include.h +../include/myslam/myslam/common_include.h + +../include/myslam/common_include.h +Eigen/Core +- +Eigen/Geometry +- +sophus/se3.h +- +sophus/so3.h +- +opencv2/core/core.hpp +- +vector +- +list +- +memory +- +string +- +iostream +- +set +- +unordered_map +- +map +- + +../include/myslam/config.h +myslam/common_include.h +../include/myslam/myslam/common_include.h + +../include/myslam/frame.h +myslam/common_include.h +../include/myslam/myslam/common_include.h +myslam/camera.h +../include/myslam/myslam/camera.h + +../include/myslam/map.h +myslam/common_include.h +../include/myslam/myslam/common_include.h +myslam/frame.h +../include/myslam/myslam/frame.h +myslam/mappoint.h +../include/myslam/myslam/mappoint.h + +../include/myslam/mappoint.h + +../include/myslam/visual_odometry.h +myslam/common_include.h +../include/myslam/myslam/common_include.h +myslam/map.h +../include/myslam/myslam/map.h +opencv2/features2d/features2d.hpp +- + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +so3.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +Eigen/Core +- +Eigen/StdVector +- +Eigen/Geometry +- + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/test/run_vo.cpp +fstream +- +boost/timer.hpp +- +opencv2/imgcodecs.hpp +- +opencv2/highgui/highgui.hpp +- +opencv2/viz.hpp +- +myslam/config.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/test/myslam/config.h +myslam/visual_odometry.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/test/myslam/visual_odometry.h + +/usr/include/eigen3/Eigen/Cholesky +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/Cholesky/LLT.h +/usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/Cholesky/LDLT.h +/usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/Cholesky/LLT_MKL.h +/usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Core/util/Macros.h +/usr/include/eigen3/Eigen/src/Core/util/Macros.h +complex +- +src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +malloc.h +- +immintrin.h +- +emmintrin.h +- +xmmintrin.h +- +pmmintrin.h +- +tmmintrin.h +- +smmintrin.h +- +nmmintrin.h +- +altivec.h +- +arm_neon.h +- +omp.h +- +cerrno +- +cstddef +- +cstdlib +- +cmath +- +cassert +- +functional +- +iosfwd +- +cstring +- +string +- +limits +- +climits +- +algorithm +- +iostream +- +intrin.h +- +new +- +src/Core/util/Constants.h +/usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/Core/util/ForwardDeclarations.h +/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/Core/util/Meta.h +/usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/Core/util/StaticAssert.h +/usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/Core/util/XprHelper.h +/usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/Core/util/Memory.h +/usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/Core/NumTraits.h +/usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/Core/MathFunctions.h +/usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/Core/GenericPacketMath.h +/usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/Core/arch/SSE/PacketMath.h +/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/Core/arch/SSE/MathFunctions.h +/usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/Core/arch/SSE/Complex.h +/usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/Core/arch/AltiVec/PacketMath.h +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/Core/arch/AltiVec/Complex.h +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/Core/arch/NEON/PacketMath.h +/usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/Core/arch/NEON/Complex.h +/usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/Core/arch/Default/Settings.h +/usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/Core/Functors.h +/usr/include/eigen3/Eigen/src/Core/Functors.h +src/Core/DenseCoeffsBase.h +/usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/Core/DenseBase.h +/usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/Core/MatrixBase.h +/usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/Core/EigenBase.h +/usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/Core/Assign.h +/usr/include/eigen3/Eigen/src/Core/Assign.h +src/Core/util/BlasUtil.h +/usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/Core/DenseStorage.h +/usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/Core/NestByValue.h +/usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/Core/ForceAlignedAccess.h +/usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/Core/ReturnByValue.h +/usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/Core/NoAlias.h +/usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/Core/PlainObjectBase.h +/usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/Core/Matrix.h +/usr/include/eigen3/Eigen/src/Core/Matrix.h +src/Core/Array.h +/usr/include/eigen3/Eigen/src/Core/Array.h +src/Core/CwiseBinaryOp.h +/usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/Core/CwiseUnaryOp.h +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/Core/CwiseNullaryOp.h +/usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/Core/CwiseUnaryView.h +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/Core/SelfCwiseBinaryOp.h +/usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/Core/Dot.h +/usr/include/eigen3/Eigen/src/Core/Dot.h +src/Core/StableNorm.h +/usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/Core/MapBase.h +/usr/include/eigen3/Eigen/src/Core/MapBase.h +src/Core/Stride.h +/usr/include/eigen3/Eigen/src/Core/Stride.h +src/Core/Map.h +/usr/include/eigen3/Eigen/src/Core/Map.h +src/Core/Block.h +/usr/include/eigen3/Eigen/src/Core/Block.h +src/Core/VectorBlock.h +/usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/Core/Ref.h +/usr/include/eigen3/Eigen/src/Core/Ref.h +src/Core/Transpose.h +/usr/include/eigen3/Eigen/src/Core/Transpose.h +src/Core/DiagonalMatrix.h +/usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/Core/Diagonal.h +/usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/Core/DiagonalProduct.h +/usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/Core/PermutationMatrix.h +/usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/Core/Transpositions.h +/usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/Core/Redux.h +/usr/include/eigen3/Eigen/src/Core/Redux.h +src/Core/Visitor.h +/usr/include/eigen3/Eigen/src/Core/Visitor.h +src/Core/Fuzzy.h +/usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/Core/IO.h +/usr/include/eigen3/Eigen/src/Core/IO.h +src/Core/Swap.h +/usr/include/eigen3/Eigen/src/Core/Swap.h +src/Core/CommaInitializer.h +/usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/Core/Flagged.h +/usr/include/eigen3/Eigen/src/Core/Flagged.h +src/Core/ProductBase.h +/usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/Core/GeneralProduct.h +/usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/Core/TriangularMatrix.h +/usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/Core/SelfAdjointView.h +/usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/Core/products/GeneralBlockPanelKernel.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/Core/products/Parallelizer.h +/usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/Core/products/CoeffBasedProduct.h +/usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/Core/products/GeneralMatrixVector.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/Core/products/GeneralMatrixMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/Core/SolveTriangular.h +/usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/Core/products/GeneralMatrixMatrixTriangular.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/Core/products/SelfadjointMatrixVector.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/Core/products/SelfadjointMatrixMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/Core/products/SelfadjointProduct.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/Core/products/SelfadjointRank2Update.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/Core/products/TriangularMatrixVector.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/Core/products/TriangularMatrixMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/Core/products/TriangularSolverMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/Core/products/TriangularSolverVector.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/Core/BandMatrix.h +/usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/Core/CoreIterators.h +/usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/Core/BooleanRedux.h +/usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/Core/Select.h +/usr/include/eigen3/Eigen/src/Core/Select.h +src/Core/VectorwiseOp.h +/usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/Core/Random.h +/usr/include/eigen3/Eigen/src/Core/Random.h +src/Core/Replicate.h +/usr/include/eigen3/Eigen/src/Core/Replicate.h +src/Core/Reverse.h +/usr/include/eigen3/Eigen/src/Core/Reverse.h +src/Core/ArrayBase.h +/usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/Core/ArrayWrapper.h +/usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/Core/products/GeneralMatrixMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/Core/products/GeneralMatrixVector_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/Core/products/SelfadjointMatrixMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/Core/products/SelfadjointMatrixVector_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/Core/products/TriangularMatrixMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/Core/products/TriangularMatrixVector_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/Core/products/TriangularSolverMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/Core/Assign_MKL.h +/usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/Core/GlobalFunctions.h +/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +Eigen2Support +/usr/include/eigen3/Eigen/Eigen2Support + +/usr/include/eigen3/Eigen/Eigen2Support +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Eigen2Support/Macros.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/Eigen2Support/Memory.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/Eigen2Support/Meta.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/Eigen2Support/Lazy.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/Eigen2Support/Cwise.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/Eigen2Support/CwiseOperators.h +/usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/Eigen2Support/TriangularSolver.h +/usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/Eigen2Support/Block.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/Eigen2Support/VectorBlock.h +/usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/Eigen2Support/Minor.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/Eigen2Support/MathFunctions.h +/usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +iostream +- + +/usr/include/eigen3/Eigen/Eigenvalues +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +Cholesky +/usr/include/eigen3/Eigen/Cholesky +Jacobi +/usr/include/eigen3/Eigen/Jacobi +Householder +/usr/include/eigen3/Eigen/Householder +LU +/usr/include/eigen3/Eigen/LU +Geometry +/usr/include/eigen3/Eigen/Geometry +src/Eigenvalues/Tridiagonalization.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/Eigenvalues/RealSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/Eigenvalues/EigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/Eigenvalues/SelfAdjointEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/Eigenvalues/HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/Eigenvalues/ComplexSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/Eigenvalues/ComplexEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/Eigenvalues/RealQZ.h +/usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/Eigenvalues/GeneralizedEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/Eigenvalues/MatrixBaseEigenvalues.h +/usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/Eigenvalues/RealSchur_MKL.h +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/Eigenvalues/ComplexSchur_MKL.h +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Geometry +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +SVD +/usr/include/eigen3/Eigen/SVD +LU +/usr/include/eigen3/Eigen/LU +limits +- +src/Geometry/OrthoMethods.h +/usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/Geometry/EulerAngles.h +/usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/Geometry/Homogeneous.h +/usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/Geometry/RotationBase.h +/usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/Geometry/Rotation2D.h +/usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/Geometry/Quaternion.h +/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/Geometry/AngleAxis.h +/usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/Geometry/Transform.h +/usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/Geometry/Translation.h +/usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/Geometry/Scaling.h +/usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/Geometry/Hyperplane.h +/usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/Geometry/ParametrizedLine.h +/usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/Geometry/AlignedBox.h +/usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/Geometry/Umeyama.h +/usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/Geometry/arch/Geometry_SSE.h +/usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/Eigen2Support/Geometry/All.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Householder +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Householder/Householder.h +/usr/include/eigen3/Eigen/src/Householder/Householder.h +src/Householder/HouseholderSequence.h +/usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/Householder/BlockHouseholder.h +/usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Jacobi +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Jacobi/Jacobi.h +/usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/LU +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/misc/Kernel.h +/usr/include/eigen3/Eigen/src/misc/Kernel.h +src/misc/Image.h +/usr/include/eigen3/Eigen/src/misc/Image.h +src/LU/FullPivLU.h +/usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/LU/PartialPivLU.h +/usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/LU/PartialPivLU_MKL.h +/usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/LU/Determinant.h +/usr/include/eigen3/Eigen/src/LU/Determinant.h +src/LU/Inverse.h +/usr/include/eigen3/Eigen/src/LU/Inverse.h +src/LU/arch/Inverse_SSE.h +/usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/Eigen2Support/LU.h +/usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/QR +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +Cholesky +/usr/include/eigen3/Eigen/Cholesky +Jacobi +/usr/include/eigen3/Eigen/Jacobi +Householder +/usr/include/eigen3/Eigen/Householder +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/QR/HouseholderQR.h +/usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/QR/FullPivHouseholderQR.h +/usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/QR/ColPivHouseholderQR.h +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/QR/HouseholderQR_MKL.h +/usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/QR/ColPivHouseholderQR_MKL.h +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/Eigen2Support/QR.h +/usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +Eigenvalues +/usr/include/eigen3/Eigen/Eigenvalues + +/usr/include/eigen3/Eigen/SVD +QR +/usr/include/eigen3/Eigen/QR +Householder +/usr/include/eigen3/Eigen/Householder +Jacobi +/usr/include/eigen3/Eigen/Jacobi +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/SVD/JacobiSVD.h +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/SVD/JacobiSVD_MKL.h +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/SVD/UpperBidiagonalization.h +/usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/Eigen2Support/SVD.h +/usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/StdVector +Core +/usr/include/eigen3/Eigen/Core +vector +- +src/StlSupport/StdVector.h +/usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + +/usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + +/usr/include/eigen3/Eigen/src/Cholesky/LLT.h + +/usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Cholesky/Eigen/src/Core/util/MKL_support.h +iostream +- + +/usr/include/eigen3/Eigen/src/Core/Array.h + +/usr/include/eigen3/Eigen/src/Core/ArrayBase.h +../plugins/CommonCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +../plugins/MatrixCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +../plugins/ArrayCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +../plugins/CommonCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +../plugins/MatrixCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +../plugins/ArrayCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + +/usr/include/eigen3/Eigen/src/Core/Assign.h + +/usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + +/usr/include/eigen3/Eigen/src/Core/BandMatrix.h + +/usr/include/eigen3/Eigen/src/Core/Block.h + +/usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + +/usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + +/usr/include/eigen3/Eigen/src/Core/CoreIterators.h + +/usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + +/usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + +/usr/include/eigen3/Eigen/src/Core/DenseBase.h +../plugins/BlockMethods.h +/usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + +/usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + +/usr/include/eigen3/Eigen/src/Core/DenseStorage.h + +/usr/include/eigen3/Eigen/src/Core/Diagonal.h + +/usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + +/usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + +/usr/include/eigen3/Eigen/src/Core/Dot.h + +/usr/include/eigen3/Eigen/src/Core/EigenBase.h + +/usr/include/eigen3/Eigen/src/Core/Flagged.h + +/usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + +/usr/include/eigen3/Eigen/src/Core/Functors.h + +/usr/include/eigen3/Eigen/src/Core/Fuzzy.h + +/usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + +/usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + +/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + +/usr/include/eigen3/Eigen/src/Core/IO.h + +/usr/include/eigen3/Eigen/src/Core/Map.h + +/usr/include/eigen3/Eigen/src/Core/MapBase.h + +/usr/include/eigen3/Eigen/src/Core/MathFunctions.h + +/usr/include/eigen3/Eigen/src/Core/Matrix.h + +/usr/include/eigen3/Eigen/src/Core/MatrixBase.h +../plugins/CommonCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +../plugins/CommonCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +../plugins/MatrixCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +../plugins/MatrixCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/Core/NestByValue.h + +/usr/include/eigen3/Eigen/src/Core/NoAlias.h + +/usr/include/eigen3/Eigen/src/Core/NumTraits.h + +/usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + +/usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + +/usr/include/eigen3/Eigen/src/Core/ProductBase.h + +/usr/include/eigen3/Eigen/src/Core/Random.h + +/usr/include/eigen3/Eigen/src/Core/Redux.h + +/usr/include/eigen3/Eigen/src/Core/Ref.h + +/usr/include/eigen3/Eigen/src/Core/Replicate.h + +/usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + +/usr/include/eigen3/Eigen/src/Core/Reverse.h + +/usr/include/eigen3/Eigen/src/Core/Select.h + +/usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + +/usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + +/usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + +/usr/include/eigen3/Eigen/src/Core/StableNorm.h + +/usr/include/eigen3/Eigen/src/Core/Stride.h + +/usr/include/eigen3/Eigen/src/Core/Swap.h + +/usr/include/eigen3/Eigen/src/Core/Transpose.h + +/usr/include/eigen3/Eigen/src/Core/Transpositions.h + +/usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + +/usr/include/eigen3/Eigen/src/Core/VectorBlock.h + +/usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + +/usr/include/eigen3/Eigen/src/Core/Visitor.h + +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + +/usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + +/usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + +/usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + +/usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + +/usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + +/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + +/usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + +/usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + +/usr/include/eigen3/Eigen/src/Core/util/Constants.h + +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + +/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + +/usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +mkl.h +- +mkl_lapacke.h +- + +/usr/include/eigen3/Eigen/src/Core/util/Macros.h +cstdlib +- +iostream +- + +/usr/include/eigen3/Eigen/src/Core/util/Memory.h +unistd.h +- + +/usr/include/eigen3/Eigen/src/Core/util/Meta.h + +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + +/usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +limits +- +RotationBase.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +Rotation2D.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +Quaternion.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +AngleAxis.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +Transform.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +Translation.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +Scaling.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +AlignedBox.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +Hyperplane.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +ParametrizedLine.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +RotationBase.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +Rotation2D.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +Quaternion.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +AngleAxis.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +Transform.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +Translation.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +Scaling.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +AlignedBox.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +Hyperplane.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +ParametrizedLine.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/././HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/././HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +./ComplexSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +./RealSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +./RealQZ.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +./Tridiagonalization.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +./Tridiagonalization.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + +/usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + +/usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + +/usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + +/usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + +/usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + +/usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + +/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + +/usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + +/usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + +/usr/include/eigen3/Eigen/src/Geometry/Scaling.h + +/usr/include/eigen3/Eigen/src/Geometry/Transform.h + +/usr/include/eigen3/Eigen/src/Geometry/Translation.h + +/usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + +/usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + +/usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + +/usr/include/eigen3/Eigen/src/Householder/Householder.h + +/usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + +/usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + +/usr/include/eigen3/Eigen/src/LU/Determinant.h + +/usr/include/eigen3/Eigen/src/LU/FullPivLU.h + +/usr/include/eigen3/Eigen/src/LU/Inverse.h + +/usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + +/usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/LU/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/QR/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + +/usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + +/usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/QR/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/SVD/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + +/usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +Eigen/src/StlSupport/details.h +/usr/include/eigen3/Eigen/src/StlSupport/Eigen/src/StlSupport/details.h + +/usr/include/eigen3/Eigen/src/StlSupport/details.h + +/usr/include/eigen3/Eigen/src/misc/Image.h + +/usr/include/eigen3/Eigen/src/misc/Kernel.h + +/usr/include/eigen3/Eigen/src/misc/Solve.h + +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + +/usr/local/include/opencv/cxcore.h +opencv2/core/core_c.h +/usr/local/include/opencv/opencv2/core/core_c.h + +/usr/local/include/opencv2/calib3d.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/opencv2/features2d.hpp +opencv2/core/affine.hpp +/usr/local/include/opencv2/opencv2/core/affine.hpp +opencv2/calib3d/calib3d_c.h +/usr/local/include/opencv2/opencv2/calib3d/calib3d_c.h + +/usr/local/include/opencv2/calib3d/calib3d_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/calib3d/opencv2/core/core_c.h + +/usr/local/include/opencv2/core.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/opencv2/core/cvdef.h +opencv2/core/version.hpp +/usr/local/include/opencv2/opencv2/core/version.hpp +opencv2/core/base.hpp +/usr/local/include/opencv2/opencv2/core/base.hpp +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/opencv2/core/cvstd.hpp +opencv2/core/traits.hpp +/usr/local/include/opencv2/opencv2/core/traits.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/opencv2/core/matx.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/opencv2/core/types.hpp +opencv2/core/mat.hpp +/usr/local/include/opencv2/opencv2/core/mat.hpp +opencv2/core/persistence.hpp +/usr/local/include/opencv2/opencv2/core/persistence.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/opencv2/opencv.hpp +opencv2/xfeatures2d.hpp +/usr/local/include/opencv2/opencv2/xfeatures2d.hpp +opencv2/core/operations.hpp +/usr/local/include/opencv2/opencv2/core/operations.hpp +opencv2/core/cvstd.inl.hpp +/usr/local/include/opencv2/opencv2/core/cvstd.inl.hpp +opencv2/core/utility.hpp +/usr/local/include/opencv2/opencv2/core/utility.hpp +opencv2/core/optim.hpp +/usr/local/include/opencv2/opencv2/core/optim.hpp + +/usr/local/include/opencv2/core/affine.hpp +opencv2/core.hpp +- + +/usr/local/include/opencv2/core/base.hpp +climits +- +algorithm +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/core/opencv2/core/cvstd.hpp +opencv2/core/neon_utils.hpp +/usr/local/include/opencv2/core/opencv2/core/neon_utils.hpp + +/usr/local/include/opencv2/core/bufferpool.hpp + +/usr/local/include/opencv2/core/core.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/core_c.h +opencv2/core/types_c.h +/usr/local/include/opencv2/core/opencv2/core/types_c.h +cxcore.h +/usr/local/include/opencv2/core/cxcore.h +cxcore.h +/usr/local/include/opencv2/core/cxcore.h +opencv2/core/utility.hpp +/usr/local/include/opencv2/core/opencv2/core/utility.hpp + +/usr/local/include/opencv2/core/cvdef.h +limits.h +- +opencv2/core/hal/interface.h +/usr/local/include/opencv2/core/opencv2/core/hal/interface.h +emmintrin.h +- +pmmintrin.h +- +tmmintrin.h +- +smmintrin.h +- +nmmintrin.h +- +nmmintrin.h +- +popcntintrin.h +- +immintrin.h +- +immintrin.h +- +Intrin.h +- +arm_neon.h +/usr/local/include/opencv2/core/arm_neon.h +arm_neon.h +- +intrin.h +- + +/usr/local/include/opencv2/core/cvstd.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +cstddef +- +cstring +- +cctype +- +string +- +algorithm +- +utility +- +cstdlib +- +cmath +- +opencv2/core/ptr.inl.hpp +/usr/local/include/opencv2/core/opencv2/core/ptr.inl.hpp + +/usr/local/include/opencv2/core/cvstd.inl.hpp +complex +- +ostream +- + +/usr/local/include/opencv2/core/fast_math.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +fastmath.h +- +cmath +- +math.h +- +tegra_round.hpp +/usr/local/include/opencv2/core/tegra_round.hpp + +/usr/local/include/opencv2/core/hal/interface.h +cstddef +- +stddef.h +- +cstdint +- +stdint.h +- + +/usr/local/include/opencv2/core/mat.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/core/opencv2/core/matx.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/core/opencv2/core/types.hpp +opencv2/core/bufferpool.hpp +/usr/local/include/opencv2/core/opencv2/core/bufferpool.hpp +opencv2/core/mat.inl.hpp +/usr/local/include/opencv2/core/opencv2/core/mat.inl.hpp + +/usr/local/include/opencv2/core/mat.inl.hpp + +/usr/local/include/opencv2/core/matx.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/base.hpp +/usr/local/include/opencv2/core/opencv2/core/base.hpp +opencv2/core/traits.hpp +/usr/local/include/opencv2/core/opencv2/core/traits.hpp +opencv2/core/saturate.hpp +/usr/local/include/opencv2/core/opencv2/core/saturate.hpp + +/usr/local/include/opencv2/core/neon_utils.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h + +/usr/local/include/opencv2/core/operations.hpp +cstdio +- + +/usr/local/include/opencv2/core/optim.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/persistence.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/core/opencv2/core/types.hpp +opencv2/core/mat.hpp +/usr/local/include/opencv2/core/opencv2/core/mat.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/core/opencv2/opencv.hpp +time.h +- + +/usr/local/include/opencv2/core/ptr.inl.hpp +algorithm +- + +/usr/local/include/opencv2/core/saturate.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/fast_math.hpp +/usr/local/include/opencv2/core/opencv2/core/fast_math.hpp + +/usr/local/include/opencv2/core/traits.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h + +/usr/local/include/opencv2/core/types.hpp +climits +- +cfloat +- +vector +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/core/opencv2/core/cvstd.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/core/opencv2/core/matx.hpp + +/usr/local/include/opencv2/core/types_c.h +ipl.h +- +ipl/ipl.h +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +assert.h +- +stdlib.h +- +string.h +- +float.h +- +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/utility.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp +opencv2/core/core_c.h +/usr/local/include/opencv2/core/opencv2/core/core_c.h + +/usr/local/include/opencv2/core/version.hpp + +/usr/local/include/opencv2/features2d.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/flann/miniflann.hpp +/usr/local/include/opencv2/opencv2/flann/miniflann.hpp + +/usr/local/include/opencv2/features2d/features2d.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/features2d/opencv2/features2d.hpp + +/usr/local/include/opencv2/flann/config.h + +/usr/local/include/opencv2/flann/defines.h +config.h +/usr/local/include/opencv2/flann/config.h + +/usr/local/include/opencv2/flann/miniflann.hpp +opencv2/core.hpp +/usr/local/include/opencv2/flann/opencv2/core.hpp +opencv2/flann/defines.h +/usr/local/include/opencv2/flann/opencv2/flann/defines.h + +/usr/local/include/opencv2/highgui.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgcodecs.hpp +/usr/local/include/opencv2/opencv2/imgcodecs.hpp +opencv2/videoio.hpp +/usr/local/include/opencv2/opencv2/videoio.hpp +opencv2/highgui/highgui_c.h +/usr/local/include/opencv2/opencv2/highgui/highgui_c.h + +/usr/local/include/opencv2/highgui/highgui.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/highgui/opencv2/highgui.hpp + +/usr/local/include/opencv2/highgui/highgui_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/highgui/opencv2/core/core_c.h +opencv2/imgproc/imgproc_c.h +/usr/local/include/opencv2/highgui/opencv2/imgproc/imgproc_c.h +opencv2/imgcodecs/imgcodecs_c.h +/usr/local/include/opencv2/highgui/opencv2/imgcodecs/imgcodecs_c.h +opencv2/videoio/videoio_c.h +/usr/local/include/opencv2/highgui/opencv2/videoio/videoio_c.h + +/usr/local/include/opencv2/imgcodecs.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/opencv.hpp +- + +/usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/imgcodecs/opencv2/core/core_c.h + +/usr/local/include/opencv2/imgproc.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/core.hpp +- +opencv2/imgproc.hpp +- +opencv2/imgcodecs.hpp +- +opencv2/highgui.hpp +- +iostream +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +math.h +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/opencv2/highgui.hpp +opencv2/imgproc/imgproc_c.h +/usr/local/include/opencv2/opencv2/imgproc/imgproc_c.h + +/usr/local/include/opencv2/imgproc/imgproc_c.h +opencv2/imgproc/types_c.h +/usr/local/include/opencv2/imgproc/opencv2/imgproc/types_c.h + +/usr/local/include/opencv2/imgproc/types_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/imgproc/opencv2/core/core_c.h + +/usr/local/include/opencv2/ml.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +float.h +- +map +- +iostream +- + +/usr/local/include/opencv2/objdetect.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/objdetect/detection_based_tracker.hpp +/usr/local/include/opencv2/opencv2/objdetect/detection_based_tracker.hpp +opencv2/objdetect/objdetect_c.h +/usr/local/include/opencv2/opencv2/objdetect/objdetect_c.h + +/usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +vector +- + +/usr/local/include/opencv2/objdetect/objdetect_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/objdetect/opencv2/core/core_c.h +deque +- +vector +- + +/usr/local/include/opencv2/opencv.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/photo.hpp +/usr/local/include/opencv2/opencv2/photo.hpp +opencv2/video.hpp +/usr/local/include/opencv2/opencv2/video.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/opencv2/features2d.hpp +opencv2/objdetect.hpp +/usr/local/include/opencv2/opencv2/objdetect.hpp +opencv2/calib3d.hpp +/usr/local/include/opencv2/opencv2/calib3d.hpp +opencv2/imgcodecs.hpp +/usr/local/include/opencv2/opencv2/imgcodecs.hpp +opencv2/videoio.hpp +/usr/local/include/opencv2/opencv2/videoio.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/opencv2/highgui.hpp +opencv2/ml.hpp +/usr/local/include/opencv2/opencv2/ml.hpp + +/usr/local/include/opencv2/photo.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/photo/photo_c.h +/usr/local/include/opencv2/opencv2/photo/photo_c.h + +/usr/local/include/opencv2/photo/photo_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/photo/opencv2/core/core_c.h + +/usr/local/include/opencv2/video.hpp +opencv2/video/tracking.hpp +/usr/local/include/opencv2/opencv2/video/tracking.hpp +opencv2/video/background_segm.hpp +/usr/local/include/opencv2/opencv2/video/background_segm.hpp +opencv2/video/tracking_c.h +/usr/local/include/opencv2/opencv2/video/tracking_c.h + +/usr/local/include/opencv2/video/background_segm.hpp +opencv2/core.hpp +/usr/local/include/opencv2/video/opencv2/core.hpp + +/usr/local/include/opencv2/video/tracking.hpp +opencv2/core.hpp +/usr/local/include/opencv2/video/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/video/opencv2/imgproc.hpp + +/usr/local/include/opencv2/video/tracking_c.h +opencv2/imgproc/types_c.h +/usr/local/include/opencv2/video/opencv2/imgproc/types_c.h + +/usr/local/include/opencv2/videoio.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/opencv2/opencv.hpp + +/usr/local/include/opencv2/videoio/videoio_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/videoio/opencv2/core/core_c.h + +/usr/local/include/opencv2/viz.hpp +opencv2/viz/types.hpp +- +opencv2/viz/widgets.hpp +- +opencv2/viz/viz3d.hpp +- +opencv2/viz/vizcore.hpp +- + +/usr/local/include/opencv2/viz/types.hpp +string +- +opencv2/core.hpp +- +opencv2/core/affine.hpp +- + +/usr/local/include/opencv2/viz/viz3d.hpp +opencv2/core.hpp +- +opencv2/viz/types.hpp +- +opencv2/viz/widgets.hpp +- + +/usr/local/include/opencv2/viz/vizcore.hpp +opencv2/viz/types.hpp +- +opencv2/viz/widgets.hpp +- +opencv2/viz/viz3d.hpp +- + +/usr/local/include/opencv2/viz/widgets.hpp +opencv2/viz/types.hpp +- + diff --git a/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/DependInfo.cmake b/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/DependInfo.cmake new file mode 100644 index 00000000..10556838 --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/DependInfo.cmake @@ -0,0 +1,26 @@ +# The set of languages for which implicit dependencies are needed: +SET(CMAKE_DEPENDS_LANGUAGES + "CXX" + ) +# The set of files for implicit dependencies of each language: +SET(CMAKE_DEPENDS_CHECK_CXX + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/test/run_vo.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/run_vo.cpp.o" + ) +SET(CMAKE_CXX_COMPILER_ID "GNU") + +# Targets to which this target links. +SET(CMAKE_TARGET_LINKED_INFO_FILES + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/src/CMakeFiles/myslam.dir/DependInfo.cmake" + ) + +# The include file search paths: +SET(CMAKE_C_TARGET_INCLUDE_PATH + "/usr/include/eigen3" + "/usr/local/include/opencv" + "/usr/local/include" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus" + "../include" + ) +SET(CMAKE_CXX_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) +SET(CMAKE_Fortran_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) +SET(CMAKE_ASM_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) diff --git a/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/build.make b/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/build.make new file mode 100644 index 00000000..29a5d617 --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/build.make @@ -0,0 +1,121 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2" + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" + +# Include any dependencies generated for this target. +include test/CMakeFiles/run_vo.dir/depend.make + +# Include the progress variables for this target. +include test/CMakeFiles/run_vo.dir/progress.make + +# Include the compile flags for this target's objects. +include test/CMakeFiles/run_vo.dir/flags.make + +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: test/CMakeFiles/run_vo.dir/flags.make +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: ../test/run_vo.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles" $(CMAKE_PROGRESS_1) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object test/CMakeFiles/run_vo.dir/run_vo.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/test" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/run_vo.dir/run_vo.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/test/run_vo.cpp" + +test/CMakeFiles/run_vo.dir/run_vo.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/run_vo.dir/run_vo.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/test" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/test/run_vo.cpp" > CMakeFiles/run_vo.dir/run_vo.cpp.i + +test/CMakeFiles/run_vo.dir/run_vo.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/run_vo.dir/run_vo.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/test" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/test/run_vo.cpp" -o CMakeFiles/run_vo.dir/run_vo.cpp.s + +test/CMakeFiles/run_vo.dir/run_vo.cpp.o.requires: +.PHONY : test/CMakeFiles/run_vo.dir/run_vo.cpp.o.requires + +test/CMakeFiles/run_vo.dir/run_vo.cpp.o.provides: test/CMakeFiles/run_vo.dir/run_vo.cpp.o.requires + $(MAKE) -f test/CMakeFiles/run_vo.dir/build.make test/CMakeFiles/run_vo.dir/run_vo.cpp.o.provides.build +.PHONY : test/CMakeFiles/run_vo.dir/run_vo.cpp.o.provides + +test/CMakeFiles/run_vo.dir/run_vo.cpp.o.provides.build: test/CMakeFiles/run_vo.dir/run_vo.cpp.o + +# Object files for target run_vo +run_vo_OBJECTS = \ +"CMakeFiles/run_vo.dir/run_vo.cpp.o" + +# External object files for target run_vo +run_vo_EXTERNAL_OBJECTS = + +../bin/run_vo: test/CMakeFiles/run_vo.dir/run_vo.cpp.o +../bin/run_vo: test/CMakeFiles/run_vo.dir/build.make +../bin/run_vo: ../lib/libmyslam.so +../bin/run_vo: /usr/local/lib/libopencv_viz.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_videostab.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_superres.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_stitching.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_shape.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_video.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_photo.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_objdetect.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_calib3d.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_features2d.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_ml.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_highgui.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_videoio.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_imgcodecs.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_imgproc.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_flann.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_core.so.3.1.0 +../bin/run_vo: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build/libSophus.so +../bin/run_vo: test/CMakeFiles/run_vo.dir/link.txt + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --red --bold "Linking CXX executable ../../bin/run_vo" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/test" && $(CMAKE_COMMAND) -E cmake_link_script CMakeFiles/run_vo.dir/link.txt --verbose=$(VERBOSE) + +# Rule to build all files generated by this target. +test/CMakeFiles/run_vo.dir/build: ../bin/run_vo +.PHONY : test/CMakeFiles/run_vo.dir/build + +test/CMakeFiles/run_vo.dir/requires: test/CMakeFiles/run_vo.dir/run_vo.cpp.o.requires +.PHONY : test/CMakeFiles/run_vo.dir/requires + +test/CMakeFiles/run_vo.dir/clean: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/test" && $(CMAKE_COMMAND) -P CMakeFiles/run_vo.dir/cmake_clean.cmake +.PHONY : test/CMakeFiles/run_vo.dir/clean + +test/CMakeFiles/run_vo.dir/depend: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/test" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/test" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/DependInfo.cmake" --color=$(COLOR) +.PHONY : test/CMakeFiles/run_vo.dir/depend + diff --git a/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/cmake_clean.cmake b/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/cmake_clean.cmake new file mode 100644 index 00000000..6f7a8a1e --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/cmake_clean.cmake @@ -0,0 +1,10 @@ +FILE(REMOVE_RECURSE + "CMakeFiles/run_vo.dir/run_vo.cpp.o" + "../../bin/run_vo.pdb" + "../../bin/run_vo" +) + +# Per-language clean rules from dependency scanning. +FOREACH(lang CXX) + INCLUDE(CMakeFiles/run_vo.dir/cmake_clean_${lang}.cmake OPTIONAL) +ENDFOREACH(lang) diff --git a/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/depend.internal b/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/depend.internal new file mode 100644 index 00000000..361befcf --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/depend.internal @@ -0,0 +1,277 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +test/CMakeFiles/run_vo.dir/run_vo.cpp.o + ../include/myslam/camera.h + ../include/myslam/common_include.h + ../include/myslam/config.h + ../include/myslam/frame.h + ../include/myslam/map.h + ../include/myslam/mappoint.h + ../include/myslam/visual_odometry.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/test/run_vo.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/features2d/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h + /usr/local/include/opencv2/viz.hpp + /usr/local/include/opencv2/viz/types.hpp + /usr/local/include/opencv2/viz/viz3d.hpp + /usr/local/include/opencv2/viz/vizcore.hpp + /usr/local/include/opencv2/viz/widgets.hpp diff --git a/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/depend.make b/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/depend.make new file mode 100644 index 00000000..359a10de --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/depend.make @@ -0,0 +1,277 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: ../include/myslam/camera.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: ../include/myslam/common_include.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: ../include/myslam/config.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: ../include/myslam/frame.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: ../include/myslam/map.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: ../include/myslam/mappoint.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: ../include/myslam/visual_odometry.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: ../test/run_vo.cpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/Cholesky +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/Core +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/Geometry +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/Householder +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/Jacobi +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/LU +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/QR +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/SVD +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/StdVector +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv/cxcore.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/calib3d.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/affine.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/base.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/core.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/core_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/cvdef.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/mat.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/matx.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/operations.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/optim.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/traits.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/types.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/types_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/utility.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/version.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/features2d.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/features2d/features2d.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/flann/config.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/flann/defines.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/highgui.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/highgui/highgui.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/imgproc.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/ml.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/objdetect.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/opencv.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/photo.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/video.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/videoio.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/viz.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/viz/types.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/viz/viz3d.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/viz/vizcore.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/viz/widgets.hpp + diff --git a/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/flags.make b/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/flags.make new file mode 100644 index 00000000..3b7a1c19 --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/flags.make @@ -0,0 +1,8 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# compile CXX with g++ +CXX_FLAGS = -std=c++11 -march=native -O3 -O3 -DNDEBUG -I/usr/include/eigen3 -I/usr/local/include/opencv -I/usr/local/include -I/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus -I"/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/include" + +CXX_DEFINES = + diff --git a/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/link.txt b/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/link.txt new file mode 100644 index 00000000..fc437648 --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/link.txt @@ -0,0 +1 @@ +g++ -std=c++11 -march=native -O3 -O3 -DNDEBUG CMakeFiles/run_vo.dir/run_vo.cpp.o -o ../../bin/run_vo -rdynamic ../../lib/libmyslam.so /usr/local/lib/libopencv_viz.so.3.1.0 /usr/local/lib/libopencv_videostab.so.3.1.0 /usr/local/lib/libopencv_superres.so.3.1.0 /usr/local/lib/libopencv_stitching.so.3.1.0 /usr/local/lib/libopencv_shape.so.3.1.0 /usr/local/lib/libopencv_video.so.3.1.0 /usr/local/lib/libopencv_photo.so.3.1.0 /usr/local/lib/libopencv_objdetect.so.3.1.0 /usr/local/lib/libopencv_calib3d.so.3.1.0 /usr/local/lib/libopencv_features2d.so.3.1.0 /usr/local/lib/libopencv_ml.so.3.1.0 /usr/local/lib/libopencv_highgui.so.3.1.0 /usr/local/lib/libopencv_videoio.so.3.1.0 /usr/local/lib/libopencv_imgcodecs.so.3.1.0 /usr/local/lib/libopencv_imgproc.so.3.1.0 /usr/local/lib/libopencv_flann.so.3.1.0 /usr/local/lib/libopencv_core.so.3.1.0 /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build/libSophus.so -lg2o_core -lg2o_stuff -lg2o_types_sba -Wl,-rpath,"/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/lib:/usr/local/lib:/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build" diff --git a/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/progress.make b/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/progress.make new file mode 100644 index 00000000..68e0bc5f --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/progress.make @@ -0,0 +1,2 @@ +CMAKE_PROGRESS_1 = 7 + diff --git a/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/run_vo.cpp.o b/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/run_vo.cpp.o new file mode 100644 index 00000000..9a4aeb6e Binary files /dev/null and b/vSLAM/ch9 project/0.2/build/test/CMakeFiles/run_vo.dir/run_vo.cpp.o differ diff --git a/vSLAM/ch9 project/0.2/build/test/Makefile b/vSLAM/ch9 project/0.2/build/test/Makefile new file mode 100644 index 00000000..36946321 --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/test/Makefile @@ -0,0 +1,164 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Default target executed when no arguments are given to make. +default_target: all +.PHONY : default_target + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2" + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" + +#============================================================================= +# Targets provided globally by CMake. + +# Special rule for the target edit_cache +edit_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running interactive CMake command-line interface..." + /usr/bin/cmake -i . +.PHONY : edit_cache + +# Special rule for the target edit_cache +edit_cache/fast: edit_cache +.PHONY : edit_cache/fast + +# Special rule for the target rebuild_cache +rebuild_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake to regenerate build system..." + /usr/bin/cmake -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) +.PHONY : rebuild_cache + +# Special rule for the target rebuild_cache +rebuild_cache/fast: rebuild_cache +.PHONY : rebuild_cache/fast + +# The main all target +all: cmake_check_build_system + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/test/CMakeFiles/progress.marks" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f CMakeFiles/Makefile2 test/all + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build/CMakeFiles" 0 +.PHONY : all + +# The main clean target +clean: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f CMakeFiles/Makefile2 test/clean +.PHONY : clean + +# The main clean target +clean/fast: clean +.PHONY : clean/fast + +# Prepare targets for installation. +preinstall: all + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f CMakeFiles/Makefile2 test/preinstall +.PHONY : preinstall + +# Prepare targets for installation. +preinstall/fast: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f CMakeFiles/Makefile2 test/preinstall +.PHONY : preinstall/fast + +# clear depends +depend: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 1 +.PHONY : depend + +# Convenience name for target. +test/CMakeFiles/run_vo.dir/rule: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f CMakeFiles/Makefile2 test/CMakeFiles/run_vo.dir/rule +.PHONY : test/CMakeFiles/run_vo.dir/rule + +# Convenience name for target. +run_vo: test/CMakeFiles/run_vo.dir/rule +.PHONY : run_vo + +# fast build rule for target. +run_vo/fast: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f test/CMakeFiles/run_vo.dir/build.make test/CMakeFiles/run_vo.dir/build +.PHONY : run_vo/fast + +run_vo.o: run_vo.cpp.o +.PHONY : run_vo.o + +# target to build an object file +run_vo.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f test/CMakeFiles/run_vo.dir/build.make test/CMakeFiles/run_vo.dir/run_vo.cpp.o +.PHONY : run_vo.cpp.o + +run_vo.i: run_vo.cpp.i +.PHONY : run_vo.i + +# target to preprocess a source file +run_vo.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f test/CMakeFiles/run_vo.dir/build.make test/CMakeFiles/run_vo.dir/run_vo.cpp.i +.PHONY : run_vo.cpp.i + +run_vo.s: run_vo.cpp.s +.PHONY : run_vo.s + +# target to generate assembly for a file +run_vo.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(MAKE) -f test/CMakeFiles/run_vo.dir/build.make test/CMakeFiles/run_vo.dir/run_vo.cpp.s +.PHONY : run_vo.cpp.s + +# Help Target +help: + @echo "The following are some of the valid targets for this Makefile:" + @echo "... all (the default if no target is provided)" + @echo "... clean" + @echo "... depend" + @echo "... edit_cache" + @echo "... rebuild_cache" + @echo "... run_vo" + @echo "... run_vo.o" + @echo "... run_vo.i" + @echo "... run_vo.s" +.PHONY : help + + + +#============================================================================= +# Special targets to cleanup operation of make. + +# Special rule to run CMake to check the build system integrity. +# No rule that depends on this can have commands that come from listfiles +# because they might be regenerated. +cmake_check_build_system: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/build" && $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0 +.PHONY : cmake_check_build_system + diff --git a/vSLAM/ch9 project/0.2/build/test/cmake_install.cmake b/vSLAM/ch9 project/0.2/build/test/cmake_install.cmake new file mode 100644 index 00000000..f5f901ee --- /dev/null +++ b/vSLAM/ch9 project/0.2/build/test/cmake_install.cmake @@ -0,0 +1,34 @@ +# Install script for directory: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.2/test + +# Set the install prefix +IF(NOT DEFINED CMAKE_INSTALL_PREFIX) + SET(CMAKE_INSTALL_PREFIX "/usr/local") +ENDIF(NOT DEFINED CMAKE_INSTALL_PREFIX) +STRING(REGEX REPLACE "/$" "" CMAKE_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}") + +# Set the install configuration name. +IF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + IF(BUILD_TYPE) + STRING(REGEX REPLACE "^[^A-Za-z0-9_]+" "" + CMAKE_INSTALL_CONFIG_NAME "${BUILD_TYPE}") + ELSE(BUILD_TYPE) + SET(CMAKE_INSTALL_CONFIG_NAME "Release") + ENDIF(BUILD_TYPE) + MESSAGE(STATUS "Install configuration: \"${CMAKE_INSTALL_CONFIG_NAME}\"") +ENDIF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + +# Set the component getting installed. +IF(NOT CMAKE_INSTALL_COMPONENT) + IF(COMPONENT) + MESSAGE(STATUS "Install component: \"${COMPONENT}\"") + SET(CMAKE_INSTALL_COMPONENT "${COMPONENT}") + ELSE(COMPONENT) + SET(CMAKE_INSTALL_COMPONENT) + ENDIF(COMPONENT) +ENDIF(NOT CMAKE_INSTALL_COMPONENT) + +# Install shared libraries without execute permission? +IF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + SET(CMAKE_INSTALL_SO_NO_EXE "1") +ENDIF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + diff --git a/vSLAM/ch9 project/0.2/cmake_modules/FindCSparse.cmake b/vSLAM/ch9 project/0.2/cmake_modules/FindCSparse.cmake new file mode 100644 index 00000000..f31df8de --- /dev/null +++ b/vSLAM/ch9 project/0.2/cmake_modules/FindCSparse.cmake @@ -0,0 +1,25 @@ +# Look for csparse; note the difference in the directory specifications! +FIND_PATH(CSPARSE_INCLUDE_DIR NAMES cs.h + PATHS + /usr/include/suitesparse + /usr/include + /opt/local/include + /usr/local/include + /sw/include + /usr/include/ufsparse + /opt/local/include/ufsparse + /usr/local/include/ufsparse + /sw/include/ufsparse + ) + +FIND_LIBRARY(CSPARSE_LIBRARY NAMES cxsparse + PATHS + /usr/lib + /usr/local/lib + /opt/local/lib + /sw/lib + ) + +include(FindPackageHandleStandardArgs) +find_package_handle_standard_args(CSPARSE DEFAULT_MSG + CSPARSE_INCLUDE_DIR CSPARSE_LIBRARY) diff --git a/vSLAM/ch9 project/0.2/cmake_modules/FindG2O.cmake b/vSLAM/ch9 project/0.2/cmake_modules/FindG2O.cmake new file mode 100644 index 00000000..655600fb --- /dev/null +++ b/vSLAM/ch9 project/0.2/cmake_modules/FindG2O.cmake @@ -0,0 +1,113 @@ +# Find the header files + +FIND_PATH(G2O_INCLUDE_DIR g2o/core/base_vertex.h + ${G2O_ROOT}/include + $ENV{G2O_ROOT}/include + $ENV{G2O_ROOT} + /usr/local/include + /usr/include + /opt/local/include + /sw/local/include + /sw/include + NO_DEFAULT_PATH + ) + +# Macro to unify finding both the debug and release versions of the +# libraries; this is adapted from the OpenSceneGraph FIND_LIBRARY +# macro. + +MACRO(FIND_G2O_LIBRARY MYLIBRARY MYLIBRARYNAME) + + FIND_LIBRARY("${MYLIBRARY}_DEBUG" + NAMES "g2o_${MYLIBRARYNAME}_d" + PATHS + ${G2O_ROOT}/lib/Debug + ${G2O_ROOT}/lib + $ENV{G2O_ROOT}/lib/Debug + $ENV{G2O_ROOT}/lib + NO_DEFAULT_PATH + ) + + FIND_LIBRARY("${MYLIBRARY}_DEBUG" + NAMES "g2o_${MYLIBRARYNAME}_d" + PATHS + ~/Library/Frameworks + /Library/Frameworks + /usr/local/lib + /usr/local/lib64 + /usr/lib + /usr/lib64 + /opt/local/lib + /sw/local/lib + /sw/lib + ) + + FIND_LIBRARY(${MYLIBRARY} + NAMES "g2o_${MYLIBRARYNAME}" + PATHS + ${G2O_ROOT}/lib/Release + ${G2O_ROOT}/lib + $ENV{G2O_ROOT}/lib/Release + $ENV{G2O_ROOT}/lib + NO_DEFAULT_PATH + ) + + FIND_LIBRARY(${MYLIBRARY} + NAMES "g2o_${MYLIBRARYNAME}" + PATHS + ~/Library/Frameworks + /Library/Frameworks + /usr/local/lib + /usr/local/lib64 + /usr/lib + /usr/lib64 + /opt/local/lib + /sw/local/lib + /sw/lib + ) + + IF(NOT ${MYLIBRARY}_DEBUG) + IF(MYLIBRARY) + SET(${MYLIBRARY}_DEBUG ${MYLIBRARY}) + ENDIF(MYLIBRARY) + ENDIF( NOT ${MYLIBRARY}_DEBUG) + +ENDMACRO(FIND_G2O_LIBRARY LIBRARY LIBRARYNAME) + +# Find the core elements +FIND_G2O_LIBRARY(G2O_STUFF_LIBRARY stuff) +FIND_G2O_LIBRARY(G2O_CORE_LIBRARY core) + +# Find the CLI library +FIND_G2O_LIBRARY(G2O_CLI_LIBRARY cli) + +# Find the pluggable solvers +FIND_G2O_LIBRARY(G2O_SOLVER_CHOLMOD solver_cholmod) +FIND_G2O_LIBRARY(G2O_SOLVER_CSPARSE solver_csparse) +FIND_G2O_LIBRARY(G2O_SOLVER_CSPARSE_EXTENSION csparse_extension) +FIND_G2O_LIBRARY(G2O_SOLVER_DENSE solver_dense) +FIND_G2O_LIBRARY(G2O_SOLVER_PCG solver_pcg) +FIND_G2O_LIBRARY(G2O_SOLVER_SLAM2D_LINEAR solver_slam2d_linear) +FIND_G2O_LIBRARY(G2O_SOLVER_STRUCTURE_ONLY solver_structure_only) +FIND_G2O_LIBRARY(G2O_SOLVER_EIGEN solver_eigen) + +# Find the predefined types +FIND_G2O_LIBRARY(G2O_TYPES_DATA types_data) +FIND_G2O_LIBRARY(G2O_TYPES_ICP types_icp) +FIND_G2O_LIBRARY(G2O_TYPES_SBA types_sba) +FIND_G2O_LIBRARY(G2O_TYPES_SCLAM2D types_sclam2d) +FIND_G2O_LIBRARY(G2O_TYPES_SIM3 types_sim3) +FIND_G2O_LIBRARY(G2O_TYPES_SLAM2D types_slam2d) +FIND_G2O_LIBRARY(G2O_TYPES_SLAM3D types_slam3d) + +# G2O solvers declared found if we found at least one solver +SET(G2O_SOLVERS_FOUND "NO") +IF(G2O_SOLVER_CHOLMOD OR G2O_SOLVER_CSPARSE OR G2O_SOLVER_DENSE OR G2O_SOLVER_PCG OR G2O_SOLVER_SLAM2D_LINEAR OR G2O_SOLVER_STRUCTURE_ONLY OR G2O_SOLVER_EIGEN) + SET(G2O_SOLVERS_FOUND "YES") +ENDIF(G2O_SOLVER_CHOLMOD OR G2O_SOLVER_CSPARSE OR G2O_SOLVER_DENSE OR G2O_SOLVER_PCG OR G2O_SOLVER_SLAM2D_LINEAR OR G2O_SOLVER_STRUCTURE_ONLY OR G2O_SOLVER_EIGEN) + +# G2O itself declared found if we found the core libraries and at least one solver +SET(G2O_FOUND "NO") +IF(G2O_STUFF_LIBRARY AND G2O_CORE_LIBRARY AND G2O_INCLUDE_DIR AND G2O_SOLVERS_FOUND) + SET(G2O_FOUND "YES") +ENDIF(G2O_STUFF_LIBRARY AND G2O_CORE_LIBRARY AND G2O_INCLUDE_DIR AND G2O_SOLVERS_FOUND) diff --git a/vSLAM/ch9 project/0.2/config/default.yaml b/vSLAM/ch9 project/0.2/config/default.yaml new file mode 100644 index 00000000..8f088982 --- /dev/null +++ b/vSLAM/ch9 project/0.2/config/default.yaml @@ -0,0 +1,23 @@ +%YAML:1.0 +# data +# the tum dataset directory, change it to yours! +dataset_dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/data + +# camera intrinsics +# fr1 +camera.fx: 517.3 +camera.fy: 516.5 +camera.cx: 325.1 +camera.cy: 249.7 + +camera.depth_scale: 5000 + +# VO paras +number_of_features: 500 +scale_factor: 1.2 +level_pyramid: 8 +match_ratio: 2.0 +max_num_lost: 10 +min_inliers: 10 +keyframe_rotation: 0.1 +keyframe_translation: 0.1 diff --git a/vSLAM/ch9 project/0.2/include/myslam/camera.h b/vSLAM/ch9 project/0.2/include/myslam/camera.h new file mode 100644 index 00000000..2570ab47 --- /dev/null +++ b/vSLAM/ch9 project/0.2/include/myslam/camera.h @@ -0,0 +1,51 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifndef CAMERA_H +#define CAMERA_H + +#include "myslam/common_include.h" + +namespace myslam +{ + +// Pinhole RGBD camera model +class Camera +{ +public: + typedef std::shared_ptr Ptr; + float fx_, fy_, cx_, cy_, depth_scale_; // Camera intrinsics + + Camera(); + Camera ( float fx, float fy, float cx, float cy, float depth_scale=0 ) : + fx_ ( fx ), fy_ ( fy ), cx_ ( cx ), cy_ ( cy ), depth_scale_ ( depth_scale ) + {} + + // coordinate transform: world, camera, pixel + Vector3d world2camera( const Vector3d& p_w, const SE3& T_c_w ); + Vector3d camera2world( const Vector3d& p_c, const SE3& T_c_w ); + Vector2d camera2pixel( const Vector3d& p_c ); + Vector3d pixel2camera( const Vector2d& p_p, double depth=1 ); + Vector3d pixel2world ( const Vector2d& p_p, const SE3& T_c_w, double depth=1 ); + Vector2d world2pixel ( const Vector3d& p_w, const SE3& T_c_w ); + +}; + +} +#endif // CAMERA_H diff --git a/vSLAM/ch9 project/0.2/include/myslam/common_include.h b/vSLAM/ch9 project/0.2/include/myslam/common_include.h new file mode 100644 index 00000000..a24307e0 --- /dev/null +++ b/vSLAM/ch9 project/0.2/include/myslam/common_include.h @@ -0,0 +1,52 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + + +#ifndef COMMON_INCLUDE_H +#define COMMON_INCLUDE_H + +// define the commonly included file to avoid a long include list +// for Eigen +#include +#include +using Eigen::Vector2d; +using Eigen::Vector3d; + +// for Sophus +#include +#include +using Sophus::SE3; +using Sophus::SO3; + +// for cv +#include +using cv::Mat; + +// std +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace std; +#endif \ No newline at end of file diff --git a/vSLAM/ch9 project/0.2/include/myslam/config.h b/vSLAM/ch9 project/0.2/include/myslam/config.h new file mode 100644 index 00000000..f5c7b452 --- /dev/null +++ b/vSLAM/ch9 project/0.2/include/myslam/config.h @@ -0,0 +1,49 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifndef CONFIG_H +#define CONFIG_H + +#include "myslam/common_include.h" + +namespace myslam +{ +class Config +{ +private: + static std::shared_ptr config_; + cv::FileStorage file_; + + Config () {} // private constructor makes a singleton +public: + ~Config(); // close the file when deconstructing + + // set a new config file + static void setParameterFile( const std::string& filename ); + + // access the parameter values + template< typename T > + static T get( const std::string& key ) + { + return T( Config::config_->file_[key] ); + } +}; +} + +#endif // CONFIG_H diff --git a/vSLAM/ch9 project/0.2/include/myslam/frame.h b/vSLAM/ch9 project/0.2/include/myslam/frame.h new file mode 100644 index 00000000..561b159d --- /dev/null +++ b/vSLAM/ch9 project/0.2/include/myslam/frame.h @@ -0,0 +1,61 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifndef FRAME_H +#define FRAME_H + +#include "myslam/common_include.h" +#include "myslam/camera.h" + +namespace myslam +{ + +// forward declare +class MapPoint; +class Frame +{ +public: + typedef std::shared_ptr Ptr; + unsigned long id_; // id of this frame + double time_stamp_; // when it is recorded + SE3 T_c_w_; // transform from world to camera + Camera::Ptr camera_; // Pinhole RGBD Camera model + Mat color_, depth_; // color and depth image + +public: // data members + Frame(); + Frame( long id, double time_stamp=0, SE3 T_c_w=SE3(), Camera::Ptr camera=nullptr, Mat color=Mat(), Mat depth=Mat() ); + ~Frame(); + + // factory function + static Frame::Ptr createFrame(); + + // find the depth in depth map + double findDepth( const cv::KeyPoint& kp ); + + // Get Camera Center + Vector3d getCamCenter() const; + + // check if a point is in this frame + bool isInFrame( const Vector3d& pt_world ); +}; + +} + +#endif // FRAME_H diff --git a/vSLAM/ch9 project/0.2/include/myslam/map.h b/vSLAM/ch9 project/0.2/include/myslam/map.h new file mode 100644 index 00000000..f37547ca --- /dev/null +++ b/vSLAM/ch9 project/0.2/include/myslam/map.h @@ -0,0 +1,43 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifndef MAP_H +#define MAP_H + +#include "myslam/common_include.h" +#include "myslam/frame.h" +#include "myslam/mappoint.h" + +namespace myslam +{ +class Map +{ +public: + typedef shared_ptr Ptr; + unordered_map map_points_; // all landmarks + unordered_map keyframes_; // all key-frames + + Map() {} + + void insertKeyFrame( Frame::Ptr frame ); + void insertMapPoint( MapPoint::Ptr map_point ); +}; +} + +#endif // MAP_H diff --git a/vSLAM/ch9 project/0.2/include/myslam/mappoint.h b/vSLAM/ch9 project/0.2/include/myslam/mappoint.h new file mode 100644 index 00000000..c8ebeb31 --- /dev/null +++ b/vSLAM/ch9 project/0.2/include/myslam/mappoint.h @@ -0,0 +1,46 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifndef MAPPOINT_H +#define MAPPOINT_H + +namespace myslam +{ + +class Frame; +class MapPoint +{ +public: + typedef shared_ptr Ptr; + unsigned long id_; // ID + Vector3d pos_; // Position in world + Vector3d norm_; // Normal of viewing direction + Mat descriptor_; // Descriptor for matching + int observed_times_; // being observed by feature matching algo. + int matched_times_; // being an inliner in pose estimation + + MapPoint(); + MapPoint( long id, Vector3d position, Vector3d norm ); + + // factory function + static MapPoint::Ptr createMapPoint(); +}; +} + +#endif // MAPPOINT_H diff --git a/vSLAM/ch9 project/0.2/include/myslam/visual_odometry.h b/vSLAM/ch9 project/0.2/include/myslam/visual_odometry.h new file mode 100644 index 00000000..1cf8c69b --- /dev/null +++ b/vSLAM/ch9 project/0.2/include/myslam/visual_odometry.h @@ -0,0 +1,88 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +/*视觉里程记*/ +#ifndef VISUALODOMETRY_H//防止头文件重复引用 +#define VISUALODOMETRY_H//宏定义 + +#include "myslam/common_include.h"//常用的头文件 放在一起 化繁为简 +#include "myslam/map.h" + +#include + +namespace myslam //命令空间下 防止定义的出其他库里的同名函数 +{ +class VisualOdometry//视觉里程计类 +{ +public: + typedef shared_ptr Ptr;//共享指针 把 智能指针定义成 VisualOdometry的指针类型 以后参数传递时 使用VisualOdometry::Ptr 类型就可以了 + enum VOState {//枚举 视觉里程计 状态 + INITIALIZING=-1,//初始化标志 + OK=0,//估计成功标志 + LOST//跟丢标志 + }; + + VOState state_; // 状态 current VO status + Map::Ptr map_; // 地图 所有的帧和特征点/地标 map with all frames and map points + Frame::Ptr ref_; // 上一次帧 参考帧 reference frame + Frame::Ptr curr_; // 当前帧 current frame + + cv::Ptr orb_; // orb特征检测 orb detector and computer + vector pts_3d_ref_; // 参考帧 中的点 3d points in reference frame + vector keypoints_curr_;// 当前帧 中的 关键点 keypoints in current frame + Mat descriptors_curr_; // 当前帧中的描述子 descriptor in current frame + Mat descriptors_ref_; // 参考帧中的描述子 descriptor in reference frame + vector feature_matches_;//特征点的匹配 特征点对于描述子 之间的 字符串距离 + + SE3 T_c_r_estimated_; // 估计的坐标转换 the estimated pose of current frame + int num_inliers_; // 特征数量 number of inlier features in icp + int num_lost_; // 丢失次数 number of lost times + + // 参数变量 parameters + int num_of_features_; // 每一对帧提取的特征对数量 number of features + double scale_factor_; // 图像金字塔尺度 scale in image pyramid + int level_pyramid_; // 图像金字塔层级数 number of pyramid levels + float match_ratio_; // 选择特征点匹配的阈值 ratio for selecting good matches + int max_num_lost_; // 连续丢失的最大次数 max number of continuous lost times + int min_inliers_; // 最少内点数量 minimum inliers + + double key_frame_min_rot; // 最小的旋转 minimal rotation of two key-frames + double key_frame_min_trans; // 最小平移 minimal translation of two key-frames + +public: // functions 公有函数 可以改成 私有private 保护protected 函数 + VisualOdometry();//VisualOdometry::VisualOdometry() ://视觉里程计类 + ~VisualOdometry(); + + bool addFrame( Frame::Ptr frame ); // 添加新的一帧 add a new frame + +protected: + // inner operation 内部函数 + void extractKeyPoints(); //提取关键点 + void computeDescriptors();//计算描述子 + void featureMatching(); //特征匹配 + void poseEstimationPnP(); //位姿估计 + void setRef3DPoints(); //设置参考点 三维坐标 + + void addKeyFrame();//添加关键帧 + bool checkEstimatedPose();//核对估计的位姿 + bool checkKeyFrame(); //检查是否为关键帧 + +}; +} + +#endif // VISUALODOMETRY_H \ No newline at end of file diff --git a/vSLAM/ch9 project/0.2/lib/liblibmyslam.a b/vSLAM/ch9 project/0.2/lib/liblibmyslam.a new file mode 100644 index 00000000..46f62f98 Binary files /dev/null and b/vSLAM/ch9 project/0.2/lib/liblibmyslam.a differ diff --git a/vSLAM/ch9 project/0.2/lib/libmyslam.so b/vSLAM/ch9 project/0.2/lib/libmyslam.so new file mode 100755 index 00000000..1a6275a6 Binary files /dev/null and b/vSLAM/ch9 project/0.2/lib/libmyslam.so differ diff --git a/vSLAM/ch9 project/0.2/src/CMakeLists.txt b/vSLAM/ch9 project/0.2/src/CMakeLists.txt new file mode 100644 index 00000000..43b8f888 --- /dev/null +++ b/vSLAM/ch9 project/0.2/src/CMakeLists.txt @@ -0,0 +1,12 @@ +add_library( myslam SHARED + frame.cpp + mappoint.cpp + map.cpp + camera.cpp + config.cpp + visual_odometry.cpp +) + +target_link_libraries( myslam + ${THIRD_PARTY_LIBS} +) diff --git a/vSLAM/ch9 project/0.2/src/camera.cpp b/vSLAM/ch9 project/0.2/src/camera.cpp new file mode 100644 index 00000000..c0274ab4 --- /dev/null +++ b/vSLAM/ch9 project/0.2/src/camera.cpp @@ -0,0 +1,73 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "myslam/camera.h" +#include "myslam/config.h" + +namespace myslam +{ + +Camera::Camera() +{ + fx_ = Config::get("camera.fx"); + fy_ = Config::get("camera.fy"); + cx_ = Config::get("camera.cx"); + cy_ = Config::get("camera.cy"); + depth_scale_ = Config::get("camera.depth_scale"); +} + +Vector3d Camera::world2camera ( const Vector3d& p_w, const SE3& T_c_w ) +{ + return T_c_w*p_w; +} + +Vector3d Camera::camera2world ( const Vector3d& p_c, const SE3& T_c_w ) +{ + return T_c_w.inverse() *p_c; +} + +Vector2d Camera::camera2pixel ( const Vector3d& p_c ) +{ + return Vector2d ( + fx_ * p_c ( 0,0 ) / p_c ( 2,0 ) + cx_, + fy_ * p_c ( 1,0 ) / p_c ( 2,0 ) + cy_ + ); +} + +Vector3d Camera::pixel2camera ( const Vector2d& p_p, double depth ) +{ + return Vector3d ( + ( p_p ( 0,0 )-cx_ ) *depth/fx_, + ( p_p ( 1,0 )-cy_ ) *depth/fy_, + depth + ); +} + +Vector2d Camera::world2pixel ( const Vector3d& p_w, const SE3& T_c_w ) +{ + return camera2pixel ( world2camera ( p_w, T_c_w ) ); +} + +Vector3d Camera::pixel2world ( const Vector2d& p_p, const SE3& T_c_w, double depth ) +{ + return camera2world ( pixel2camera ( p_p, depth ), T_c_w ); +} + + +} diff --git a/vSLAM/ch9 project/0.2/src/config.cpp b/vSLAM/ch9 project/0.2/src/config.cpp new file mode 100644 index 00000000..9817d8d5 --- /dev/null +++ b/vSLAM/ch9 project/0.2/src/config.cpp @@ -0,0 +1,46 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "myslam/config.h" + +namespace myslam +{ + +void Config::setParameterFile( const std::string& filename ) +{ + if ( config_ == nullptr ) + config_ = shared_ptr(new Config); + config_->file_ = cv::FileStorage( filename.c_str(), cv::FileStorage::READ ); + if ( config_->file_.isOpened() == false ) + { + std::cerr<<"parameter file "<file_.release(); + return; + } +} + +Config::~Config() +{ + if ( file_.isOpened() ) + file_.release(); +} + +shared_ptr Config::config_ = nullptr; + +} diff --git a/vSLAM/ch9 project/0.2/src/frame.cpp b/vSLAM/ch9 project/0.2/src/frame.cpp new file mode 100644 index 00000000..39eb268e --- /dev/null +++ b/vSLAM/ch9 project/0.2/src/frame.cpp @@ -0,0 +1,90 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "myslam/frame.h" + +namespace myslam +{ +Frame::Frame() +: id_(-1), time_stamp_(-1), camera_(nullptr) +{ + +} + +Frame::Frame ( long id, double time_stamp, SE3 T_c_w, Camera::Ptr camera, Mat color, Mat depth ) +: id_(id), time_stamp_(time_stamp), T_c_w_(T_c_w), camera_(camera), color_(color), depth_(depth) +{ + +} + +Frame::~Frame() +{ + +} + +Frame::Ptr Frame::createFrame() +{ + static long factory_id = 0; + return Frame::Ptr( new Frame(factory_id++) ); +} + +double Frame::findDepth ( const cv::KeyPoint& kp ) +{ + int x = cvRound(kp.pt.x); + int y = cvRound(kp.pt.y); + ushort d = depth_.ptr(y)[x]; + if ( d!=0 ) + { + return double(d)/camera_->depth_scale_; + } + else + { + // check the nearby points + int dx[4] = {-1,0,1,0}; + int dy[4] = {0,-1,0,1}; + for ( int i=0; i<4; i++ ) + { + d = depth_.ptr( y+dy[i] )[x+dx[i]]; + if ( d!=0 ) + { + return double(d)/camera_->depth_scale_; + } + } + } + return -1.0; +} + + +Vector3d Frame::getCamCenter() const +{ + return T_c_w_.inverse().translation(); +} + +bool Frame::isInFrame ( const Vector3d& pt_world ) +{ + Vector3d p_cam = camera_->world2camera( pt_world, T_c_w_ ); + if ( p_cam(2,0)<0 ) + return false; + Vector2d pixel = camera_->world2pixel( pt_world, T_c_w_ ); + return pixel(0,0)>0 && pixel(1,0)>0 + && pixel(0,0) + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "myslam/map.h" + +namespace myslam +{ + +void Map::insertKeyFrame ( Frame::Ptr frame ) +{ + cout<<"Key frame size = "<id_) == keyframes_.end() ) + { + keyframes_.insert( make_pair(frame->id_, frame) ); + } + else + { + keyframes_[ frame->id_ ] = frame; + } +} + +void Map::insertMapPoint ( MapPoint::Ptr map_point ) +{ + if ( map_points_.find(map_point->id_) == map_points_.end() ) + { + map_points_.insert( make_pair(map_point->id_, map_point) ); + } + else + { + map_points_[map_point->id_] = map_point; + } +} + + +} diff --git a/vSLAM/ch9 project/0.2/src/mappoint.cpp b/vSLAM/ch9 project/0.2/src/mappoint.cpp new file mode 100644 index 00000000..1fbcf690 --- /dev/null +++ b/vSLAM/ch9 project/0.2/src/mappoint.cpp @@ -0,0 +1,46 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "myslam/common_include.h" +#include "myslam/mappoint.h" + +namespace myslam +{ + +MapPoint::MapPoint() +: id_(-1), pos_(Vector3d(0,0,0)), norm_(Vector3d(0,0,0)), observed_times_(0) +{ + +} + +MapPoint::MapPoint ( long id, Vector3d position, Vector3d norm ) +: id_(id), pos_(position), norm_(norm), observed_times_(0) +{ + +} + +MapPoint::Ptr MapPoint::createMapPoint() +{ + static long factory_id = 0; + return MapPoint::Ptr( + new MapPoint( factory_id++, Vector3d(0,0,0), Vector3d(0,0,0) ) + ); +} + +} diff --git a/vSLAM/ch9 project/0.2/src/visual_odometry.cpp b/vSLAM/ch9 project/0.2/src/visual_odometry.cpp new file mode 100644 index 00000000..9d002251 --- /dev/null +++ b/vSLAM/ch9 project/0.2/src/visual_odometry.cpp @@ -0,0 +1,230 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include +#include +#include +#include +#include + +#include "myslam/config.h" +#include "myslam/visual_odometry.h" +/*视觉里程记*/ +namespace myslam//命令空间下 防止定义的出其他库里的同名函数 +{ + +VisualOdometry::VisualOdometry() ://视觉里程计类 + state_ ( INITIALIZING ), ref_ ( nullptr ), curr_ ( nullptr ), map_ ( new Map ), num_lost_ ( 0 ), num_inliers_ ( 0 ) +{ + num_of_features_ = Config::get ( "number_of_features" );// 特征数量 整型 int + scale_factor_ = Config::get ( "scale_factor" ); // 尺度因子 缩小 + level_pyramid_ = Config::get ( "level_pyramid" ); // 层级 + match_ratio_ = Config::get ( "match_ratio" ); // 匹配 参数 + max_num_lost_ = Config::get ( "max_num_lost" ); // 最大丢失次数 + min_inliers_ = Config::get ( "min_inliers" ); + key_frame_min_rot = Config::get ( "keyframe_rotation" );//最小的旋转 + key_frame_min_trans = Config::get ( "keyframe_translation" ); // 最小平移 + orb_ = cv::ORB::create ( num_of_features_, scale_factor_, level_pyramid_ );//创建orb特征 +} + +VisualOdometry::~VisualOdometry()//析构 +{ + +} +// 添加新的一帧 add a new frame +bool VisualOdometry::addFrame ( Frame::Ptr frame ) +{ + switch ( state_ ) + { + case INITIALIZING://初始化之后 + { + state_ = OK;//初始化之后切换状态为 OK + curr_ = ref_ = frame;//初始化 参考帧 当前帧 + map_->insertKeyFrame ( frame );//添加第一个关键帧 到地图内 + // extract features from first frame + extractKeyPoints();//提取关键点 + computeDescriptors();//计算描述子 + // compute the 3d position of features in ref frame + setRef3DPoints();//计算特征点的 3维坐标 + break; + } + case OK://初始化之后 + { + curr_ = frame;//新的一帧为当前帧 + extractKeyPoints();//提取关键点 + computeDescriptors();//计算描述子 + featureMatching(); //特征点匹配 得到 特征点匹配点对 + poseEstimationPnP(); //根据特征点匹配点对 计算坐标转换 及估计相机位姿 + if ( checkEstimatedPose() == true ) // a good estimation 估计的效果理想 + { + curr_->T_c_w_ = T_c_r_estimated_ * ref_->T_c_w_; // T_c_w = T_c_r*T_r_w // 当前帧的转换*参考帧的转换 ——> 起始帧到当前帧的转换 + ref_ = curr_;//迭代当前帧成参考帧 + setRef3DPoints();//计算特征点的 3维坐标 + num_lost_ = 0;//重置 丢失计数 + if ( checkKeyFrame() == true ) // is a key-frame 是关键帧吗? + { + addKeyFrame();//是关键帧的话 加入关键帧 + } + } + else // 估计的效果不理想bad estimation due to various reasons + { + num_lost_++;//认为跟丢了 + if ( num_lost_ > max_num_lost_ )//如果连续跟丢失次数 大于设置的限制 + { + state_ = LOST;//设置状态为丢失 + } + return false;//并返回错误 + } + break; + } + case LOST://在状态为 丢失的情况下 + { + cout<<"视觉里程计丢失 vo has lost."<detect ( curr_->color_, keypoints_curr_ );//对彩色图 提取orb关键点 存放在 keypoints_curr_ 当前帧 关键点 +} +//计算关键点对应的描述子 +void VisualOdometry::computeDescriptors() +{ + orb_->compute ( curr_->color_, keypoints_curr_, descriptors_curr_ ); + //输入 彩色图 关键点 得到的描述子 存放在 descriptors_curr_ 关键点对应的orb描述子 +} +//特征匹配 +void VisualOdometry::featureMatching() +{ + // match desp_ref and desp_curr, use OpenCV's brute force match + vector matches;//匹配结果 + cv::BFMatcher matcher ( cv::NORM_HAMMING );//汉明匹配器 + matcher.match ( descriptors_ref_, descriptors_curr_, matches ); + //前后两帧 的特征点描述子 进行汉明长度 匹配 匹配结果存放在 matches中(各个描述子间的距离) + // select the best matches 选择较好的特征点描述子匹配对 + + //计算最小的匹配距离 + float min_dis = std::min_element ( + matches.begin(), matches.end(), + [] ( const cv::DMatch& m1, const cv::DMatch& m2 ) + { + return m1.distance < m2.distance; + } )->distance; + + feature_matches_.clear(); + for ( cv::DMatch& m : matches ) + { + if ( m.distance < max ( min_dis*match_ratio_, 30.0 ) )//最小距离限制 30 + { + feature_matches_.push_back(m);//较小的匹配距离都是 好的匹配 特征点对 即在两幅图像中表示 世界坐标系中的同一个点 + } + } + cout<<"good matches: "<findDepth(keypoints_curr_[i]); + if ( d > 0) + { + Vector3d p_cam = ref_->camera_->pixel2camera(//像素二维坐标转换到相机三维坐标 + Vector2d(keypoints_curr_[i].pt.x, keypoints_curr_[i].pt.y), d + ); + pts_3d_ref_.push_back( cv::Point3f( p_cam(0,0), p_cam(1,0), p_cam(2,0) ));//像极坐标系下的 三维坐标 + descriptors_ref_.push_back(descriptors_curr_.row(i)); //对应的描述子 + } + } +} + +void VisualOdometry::poseEstimationPnP() +{ + // construct the 3d 2d observations + vector pts3d; + vector pts2d; + + for ( cv::DMatch m:feature_matches_ ) + { + pts3d.push_back( pts_3d_ref_[m.queryIdx] ); + pts2d.push_back( keypoints_curr_[m.trainIdx].pt ); + } + //相机内参数 + Mat K = ( cv::Mat_(3,3)<< + ref_->camera_->fx_, 0, ref_->camera_->cx_, + 0, ref_->camera_->fy_, ref_->camera_->cy_, + 0,0,1 + ); + Mat rvec, tvec, inliers; + cv::solvePnPRansac( pts3d, pts2d, K, Mat(), rvec, tvec, false, 100, 4.0, 0.99, inliers ); + num_inliers_ = inliers.rows; + cout<<"pnp inliers: "<(0,0), rvec.at(1,0), rvec.at(2,0)), + Vector3d( tvec.at(0,0), tvec.at(1,0), tvec.at(2,0)) + ); +} + +//核对估计的位姿 +bool VisualOdometry::checkEstimatedPose() +{ + // check if the estimated pose is good + if ( num_inliers_ < min_inliers_ ) + { + cout<<"reject because inlier is too small: "< 5.0 ) + { + cout<<"reject because motion is too large: "<(); + Vector3d rot = d.tail<3>(); + if ( rot.norm() >key_frame_min_rot || trans.norm() >key_frame_min_trans ) + return true; + return false; +} + +//添加关键帧 +void VisualOdometry::addKeyFrame() +{ + cout<<"adding a key-frame"<insertKeyFrame ( curr_ ); +} + +} \ No newline at end of file diff --git a/vSLAM/ch9 project/0.2/test/CMakeLists.txt b/vSLAM/ch9 project/0.2/test/CMakeLists.txt new file mode 100644 index 00000000..241c4599 --- /dev/null +++ b/vSLAM/ch9 project/0.2/test/CMakeLists.txt @@ -0,0 +1,2 @@ +add_executable( run_vo run_vo.cpp ) +target_link_libraries( run_vo myslam ) \ No newline at end of file diff --git a/vSLAM/ch9 project/0.2/test/run_vo.cpp b/vSLAM/ch9 project/0.2/test/run_vo.cpp new file mode 100644 index 00000000..585c6d19 --- /dev/null +++ b/vSLAM/ch9 project/0.2/test/run_vo.cpp @@ -0,0 +1,102 @@ +// -------------- test the visual odometry ------------- +#include +#include +#include +#include +#include + +#include "myslam/config.h" +#include "myslam/visual_odometry.h" + +int main ( int argc, char** argv ) +{ + if ( argc != 2 )// 命令行参数为 参数文件名 + { + cout<<"usage: run_vo parameter_file"< ( "dataset_dir" );//数据集文件目录 + cout<<"dataset: "< rgb_files, depth_files; + vector rgb_times, depth_times; + while ( !fin.eof() ) + { + string rgb_time, rgb_file, depth_time, depth_file; + fin>>rgb_time>>rgb_file>>depth_time>>depth_file; + //rgb图像对应时间 rgb图像 深度图像对应时间 深度图像 + rgb_times.push_back ( atof ( rgb_time.c_str() ) ); + depth_times.push_back ( atof ( depth_time.c_str() ) ); + rgb_files.push_back ( dataset_dir+"/"+rgb_file ); + depth_files.push_back ( dataset_dir+"/"+depth_file ); + + if ( fin.good() == false ) + break; + } + + myslam::Camera::Ptr camera ( new myslam::Camera );//相机模型 + + // visualization + cv::viz::Viz3d vis("Visual Odometry");//可视化 + cv::viz::WCoordinateSystem world_coor(1.0), camera_coor(0.5); + cv::Point3d cam_pos( 0, -1.0, -1.0 ), cam_focal_point(0,0,0), cam_y_dir(0,1,0); + cv::Affine3d cam_pose = cv::viz::makeCameraPose( cam_pos, cam_focal_point, cam_y_dir ); + vis.setViewerPose( cam_pose ); + + world_coor.setRenderingProperty(cv::viz::LINE_WIDTH, 2.0); + camera_coor.setRenderingProperty(cv::viz::LINE_WIDTH, 1.0); + vis.showWidget( "World", world_coor ); + vis.showWidget( "Camera", camera_coor ); + + cout<<"read total "<camera_ = camera; + pFrame->color_ = color; + pFrame->depth_ = depth; + pFrame->time_stamp_ = rgb_times[i]; + + boost::timer timer; + vo->addFrame ( pFrame ); + cout<<"VO costs time: "<state_ == myslam::VisualOdometry::LOST ) + break; + SE3 Tcw = pFrame->T_c_w_.inverse(); + + // show the map and the camera pose + cv::Affine3d M( + cv::Affine3d::Mat3( + Tcw.rotation_matrix()(0,0), Tcw.rotation_matrix()(0,1), Tcw.rotation_matrix()(0,2), + Tcw.rotation_matrix()(1,0), Tcw.rotation_matrix()(1,1), Tcw.rotation_matrix()(1,2), + Tcw.rotation_matrix()(2,0), Tcw.rotation_matrix()(2,1), Tcw.rotation_matrix()(2,2) + ), + cv::Affine3d::Vec3( + Tcw.translation()(0,0), Tcw.translation()(1,0), Tcw.translation()(2,0) + ) + ); + + cv::imshow("image", color ); + cv::waitKey(0); + // cv::waitKey(1); + vis.setWidgetPose( "Camera", M); + vis.spinOnce(1, false); + } + + return 0; +} diff --git a/vSLAM/ch9 project/0.3/.kdev4/0.3.kdev4 b/vSLAM/ch9 project/0.3/.kdev4/0.3.kdev4 new file mode 100644 index 00000000..019e6850 --- /dev/null +++ b/vSLAM/ch9 project/0.3/.kdev4/0.3.kdev4 @@ -0,0 +1,39 @@ +[Buildset] +BuildItems=@Variant(\x00\x00\x00\t\x00\x00\x00\x00\x01\x00\x00\x00\x0b\x00\x00\x00\x00\x01\x00\x00\x00\x06\x000\x00.\x003) + +[CMake] +Build Directory Count=1 +Current Build Directory Index=0 +ProjectRootRelative=./ + +[CMake][CMake Build Directory 0] +Build Directory Path=file:///home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9%20project/0.3/build +Build Type=Debug +CMake Binary=file:///usr/bin/cmake +Environment Profile= +Extra Arguments= +Install Directory=file:///usr/local + +[Launch] +Launch Configurations=Launch Configuration 0 + +[Launch][Launch Configuration 0] +Configured Launch Modes=execute +Configured Launchers=nativeAppLauncher +Name=run_vo +Type=Native Application + +[Launch][Launch Configuration 0][Data] +Arguments=../config/default.yaml +Dependencies=@Variant(\x00\x00\x00\t\x00\x00\x00\x00\x01\x00\x00\x00\x0b\x00\x00\x00\x00\x03\x00\x00\x00\x06\x000\x00.\x003\x00\x00\x00\x08\x00t\x00e\x00s\x00t\x00\x00\x00\x0c\x00r\x00u\x00n\x00_\x00v\x00o) +Dependency Action=Nothing +EnvironmentGroup=default +Executable=file:///home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9%20project/0.3/bin/run_vo +External Terminal=konsole --noclose --workdir %workdir -e %exe +Project Target=0.3,test,run_vo +Use External Terminal=false +Working Directory= +isExecutable=true + +[Project] +VersionControlSupport=kdevgit diff --git a/vSLAM/ch9 project/0.3/0.3.kdev4 b/vSLAM/ch9 project/0.3/0.3.kdev4 new file mode 100644 index 00000000..8eaf56f0 --- /dev/null +++ b/vSLAM/ch9 project/0.3/0.3.kdev4 @@ -0,0 +1,3 @@ +[Project] +Manager=KDevCMakeManager +Name=0.3 diff --git a/vSLAM/ch9 project/0.3/CMakeLists.txt b/vSLAM/ch9 project/0.3/CMakeLists.txt new file mode 100644 index 00000000..2f91c5f9 --- /dev/null +++ b/vSLAM/ch9 project/0.3/CMakeLists.txt @@ -0,0 +1,33 @@ +cmake_minimum_required( VERSION 2.8 ) +project ( myslam ) + +set( CMAKE_CXX_COMPILER "g++" ) +set( CMAKE_BUILD_TYPE "Release" ) +set( CMAKE_CXX_FLAGS "-std=c++11 -march=native -O3" ) + +list( APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules ) +set( EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin ) +set( LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib ) + +############### dependencies ###################### +# Eigen +include_directories( "/usr/include/eigen3" ) +# OpenCV +find_package( OpenCV 3.1 REQUIRED ) +include_directories( ${OpenCV_INCLUDE_DIRS} ) +# Sophus +find_package( Sophus REQUIRED ) +include_directories( ${Sophus_INCLUDE_DIRS} ) +# G2O +find_package( G2O REQUIRED ) +include_directories( ${G2O_INCLUDE_DIRS} ) + +set( THIRD_PARTY_LIBS + ${OpenCV_LIBS} + ${Sophus_LIBRARIES} + g2o_core g2o_stuff g2o_types_sba +) +############### dependencies ###################### +include_directories( ${PROJECT_SOURCE_DIR}/include ) +add_subdirectory( src ) +add_subdirectory( test ) \ No newline at end of file diff --git a/vSLAM/ch9 project/0.3/bin/run_vo b/vSLAM/ch9 project/0.3/bin/run_vo new file mode 100755 index 00000000..85404e08 Binary files /dev/null and b/vSLAM/ch9 project/0.3/bin/run_vo differ diff --git a/vSLAM/ch9 project/0.3/build/CMakeCache.txt b/vSLAM/ch9 project/0.3/build/CMakeCache.txt new file mode 100644 index 00000000..ec239656 --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/CMakeCache.txt @@ -0,0 +1,455 @@ +# This is the CMakeCache file. +# For build in directory: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build +# It was generated by CMake: /usr/bin/cmake +# You can edit this file to change values found and used by cmake. +# If you do not want to change any of the values, simply exit the editor. +# If you do want to change a value, simply edit, save, and exit the editor. +# The syntax for the file is as follows: +# KEY:TYPE=VALUE +# KEY is the name of a variable in the cache. +# TYPE is a hint to GUIs for the type of VALUE, DO NOT EDIT TYPE!. +# VALUE is the current value for the KEY. + +######################## +# EXTERNAL cache entries +######################## + +//Path to a program. +CMAKE_AR:FILEPATH=/usr/bin/ar + +//Choose the type of build, options are: None(CMAKE_CXX_FLAGS or +// CMAKE_C_FLAGS used) Debug Release RelWithDebInfo MinSizeRel. +CMAKE_BUILD_TYPE:STRING=Debug + +//Enable/Disable color output during build. +CMAKE_COLOR_MAKEFILE:BOOL=ON + +//CXX compiler. +CMAKE_CXX_COMPILER:FILEPATH=/usr/bin/c++ + +//Flags used by the compiler during all build types. +CMAKE_CXX_FLAGS:STRING= + +//Flags used by the compiler during debug builds. +CMAKE_CXX_FLAGS_DEBUG:STRING=-g + +//Flags used by the compiler during release minsize builds. +CMAKE_CXX_FLAGS_MINSIZEREL:STRING=-Os -DNDEBUG + +//Flags used by the compiler during release builds (/MD /Ob1 /Oi +// /Ot /Oy /Gs will produce slightly less optimized but smaller +// files). +CMAKE_CXX_FLAGS_RELEASE:STRING=-O3 -DNDEBUG + +//Flags used by the compiler during Release with Debug Info builds. +CMAKE_CXX_FLAGS_RELWITHDEBINFO:STRING=-O2 -g -DNDEBUG + +//C compiler. +CMAKE_C_COMPILER:FILEPATH=/usr/bin/cc + +//Flags used by the compiler during all build types. +CMAKE_C_FLAGS:STRING= + +//Flags used by the compiler during debug builds. +CMAKE_C_FLAGS_DEBUG:STRING=-g + +//Flags used by the compiler during release minsize builds. +CMAKE_C_FLAGS_MINSIZEREL:STRING=-Os -DNDEBUG + +//Flags used by the compiler during release builds (/MD /Ob1 /Oi +// /Ot /Oy /Gs will produce slightly less optimized but smaller +// files). +CMAKE_C_FLAGS_RELEASE:STRING=-O3 -DNDEBUG + +//Flags used by the compiler during Release with Debug Info builds. +CMAKE_C_FLAGS_RELWITHDEBINFO:STRING=-O2 -g -DNDEBUG + +//Flags used by the linker. +CMAKE_EXE_LINKER_FLAGS:STRING=' ' + +//Flags used by the linker during debug builds. +CMAKE_EXE_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during release minsize builds. +CMAKE_EXE_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during release builds. +CMAKE_EXE_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during Release with Debug Info builds. +CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//Enable/Disable output of compile commands during generation. +CMAKE_EXPORT_COMPILE_COMMANDS:BOOL=OFF + +//Install path prefix, prepended onto install directories. +CMAKE_INSTALL_PREFIX:PATH=/usr/local + +//Path to a program. +CMAKE_LINKER:FILEPATH=/usr/bin/ld + +//Path to a program. +CMAKE_MAKE_PROGRAM:FILEPATH=/usr/bin/make + +//Flags used by the linker during the creation of modules. +CMAKE_MODULE_LINKER_FLAGS:STRING=' ' + +//Flags used by the linker during debug builds. +CMAKE_MODULE_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during release minsize builds. +CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during release builds. +CMAKE_MODULE_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during Release with Debug Info builds. +CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//Path to a program. +CMAKE_NM:FILEPATH=/usr/bin/nm + +//Path to a program. +CMAKE_OBJCOPY:FILEPATH=/usr/bin/objcopy + +//Path to a program. +CMAKE_OBJDUMP:FILEPATH=/usr/bin/objdump + +//Value Computed by CMake +CMAKE_PROJECT_NAME:STATIC=myslam + +//Path to a program. +CMAKE_RANLIB:FILEPATH=/usr/bin/ranlib + +//Flags used by the linker during the creation of dll's. +CMAKE_SHARED_LINKER_FLAGS:STRING=' ' + +//Flags used by the linker during debug builds. +CMAKE_SHARED_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during release minsize builds. +CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during release builds. +CMAKE_SHARED_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during Release with Debug Info builds. +CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//If set, runtime paths are not added when installing shared libraries, +// but are added when building. +CMAKE_SKIP_INSTALL_RPATH:BOOL=NO + +//If set, runtime paths are not added when using shared libraries. +CMAKE_SKIP_RPATH:BOOL=NO + +//Flags used by the linker during the creation of static libraries. +CMAKE_STATIC_LINKER_FLAGS:STRING= + +//Flags used by the linker during debug builds. +CMAKE_STATIC_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during release minsize builds. +CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during release builds. +CMAKE_STATIC_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during Release with Debug Info builds. +CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//Path to a program. +CMAKE_STRIP:FILEPATH=/usr/bin/strip + +//If true, cmake will use relative paths in makefiles and projects. +CMAKE_USE_RELATIVE_PATHS:BOOL=OFF + +//If this value is on, makefiles will be generated without the +// .SILENT directive, and all commands will be echoed to the console +// during the make. This is useful for debugging only. With Visual +// Studio IDE projects all commands are done without /nologo. +CMAKE_VERBOSE_MAKEFILE:BOOL=FALSE + +//Path to a library. +G2O_CLI_LIBRARY:FILEPATH=/usr/local/lib/libg2o_cli.so + +//Path to a library. +G2O_CLI_LIBRARY_DEBUG:FILEPATH=G2O_CLI_LIBRARY_DEBUG-NOTFOUND + +//Path to a library. +G2O_CORE_LIBRARY:FILEPATH=/usr/local/lib/libg2o_core.so + +//Path to a library. +G2O_CORE_LIBRARY_DEBUG:FILEPATH=G2O_CORE_LIBRARY_DEBUG-NOTFOUND + +//Path to a file. +G2O_INCLUDE_DIR:PATH=/usr/local/include + +//Path to a library. +G2O_SOLVER_CHOLMOD:FILEPATH=/usr/local/lib/libg2o_solver_cholmod.so + +//Path to a library. +G2O_SOLVER_CHOLMOD_DEBUG:FILEPATH=G2O_SOLVER_CHOLMOD_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_CSPARSE:FILEPATH=/usr/local/lib/libg2o_solver_csparse.so + +//Path to a library. +G2O_SOLVER_CSPARSE_DEBUG:FILEPATH=G2O_SOLVER_CSPARSE_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_CSPARSE_EXTENSION:FILEPATH=/usr/local/lib/libg2o_csparse_extension.so + +//Path to a library. +G2O_SOLVER_CSPARSE_EXTENSION_DEBUG:FILEPATH=G2O_SOLVER_CSPARSE_EXTENSION_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_DENSE:FILEPATH=/usr/local/lib/libg2o_solver_dense.so + +//Path to a library. +G2O_SOLVER_DENSE_DEBUG:FILEPATH=G2O_SOLVER_DENSE_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_EIGEN:FILEPATH=/usr/local/lib/libg2o_solver_eigen.so + +//Path to a library. +G2O_SOLVER_EIGEN_DEBUG:FILEPATH=G2O_SOLVER_EIGEN_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_PCG:FILEPATH=/usr/local/lib/libg2o_solver_pcg.so + +//Path to a library. +G2O_SOLVER_PCG_DEBUG:FILEPATH=G2O_SOLVER_PCG_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_SLAM2D_LINEAR:FILEPATH=/usr/local/lib/libg2o_solver_slam2d_linear.so + +//Path to a library. +G2O_SOLVER_SLAM2D_LINEAR_DEBUG:FILEPATH=G2O_SOLVER_SLAM2D_LINEAR_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_STRUCTURE_ONLY:FILEPATH=/usr/local/lib/libg2o_solver_structure_only.so + +//Path to a library. +G2O_SOLVER_STRUCTURE_ONLY_DEBUG:FILEPATH=G2O_SOLVER_STRUCTURE_ONLY_DEBUG-NOTFOUND + +//Path to a library. +G2O_STUFF_LIBRARY:FILEPATH=/usr/local/lib/libg2o_stuff.so + +//Path to a library. +G2O_STUFF_LIBRARY_DEBUG:FILEPATH=G2O_STUFF_LIBRARY_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_DATA:FILEPATH=/usr/local/lib/libg2o_types_data.so + +//Path to a library. +G2O_TYPES_DATA_DEBUG:FILEPATH=G2O_TYPES_DATA_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_ICP:FILEPATH=/usr/local/lib/libg2o_types_icp.so + +//Path to a library. +G2O_TYPES_ICP_DEBUG:FILEPATH=G2O_TYPES_ICP_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_SBA:FILEPATH=/usr/local/lib/libg2o_types_sba.so + +//Path to a library. +G2O_TYPES_SBA_DEBUG:FILEPATH=G2O_TYPES_SBA_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_SCLAM2D:FILEPATH=/usr/local/lib/libg2o_types_sclam2d.so + +//Path to a library. +G2O_TYPES_SCLAM2D_DEBUG:FILEPATH=G2O_TYPES_SCLAM2D_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_SIM3:FILEPATH=/usr/local/lib/libg2o_types_sim3.so + +//Path to a library. +G2O_TYPES_SIM3_DEBUG:FILEPATH=G2O_TYPES_SIM3_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_SLAM2D:FILEPATH=/usr/local/lib/libg2o_types_slam2d.so + +//Path to a library. +G2O_TYPES_SLAM2D_DEBUG:FILEPATH=G2O_TYPES_SLAM2D_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_SLAM3D:FILEPATH=/usr/local/lib/libg2o_types_slam3d.so + +//Path to a library. +G2O_TYPES_SLAM3D_DEBUG:FILEPATH=G2O_TYPES_SLAM3D_DEBUG-NOTFOUND + +//Path where debug 3rdparty OpenCV dependencies are located +OpenCV_3RDPARTY_LIB_DIR_DBG:PATH=/usr/local/share/OpenCV/3rdparty/lib + +//Path where release 3rdparty OpenCV dependencies are located +OpenCV_3RDPARTY_LIB_DIR_OPT:PATH=/usr/local/share/OpenCV/3rdparty/lib + +OpenCV_CONFIG_PATH:FILEPATH=/usr/local/share/OpenCV + +//The directory containing a CMake configuration file for OpenCV. +OpenCV_DIR:PATH=/usr/local/share/OpenCV + +//Path where debug OpenCV libraries are located +OpenCV_LIB_DIR_DBG:PATH= + +//Path where release OpenCV libraries are located +OpenCV_LIB_DIR_OPT:PATH= + +//The directory containing a CMake configuration file for Sophus. +Sophus_DIR:PATH=/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build + +//Value Computed by CMake +myslam_BINARY_DIR:STATIC=/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build + +//Dependencies for the target +myslam_LIB_DEPENDS:STATIC=general;opencv_viz;general;opencv_videostab;general;opencv_videoio;general;opencv_video;general;opencv_superres;general;opencv_stitching;general;opencv_shape;general;opencv_photo;general;opencv_objdetect;general;opencv_ml;general;opencv_imgproc;general;opencv_imgcodecs;general;opencv_highgui;general;opencv_flann;general;opencv_features2d;general;opencv_core;general;opencv_calib3d;general;/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build/libSophus.so;general;g2o_core;general;g2o_stuff;general;g2o_types_sba; + +//Value Computed by CMake +myslam_SOURCE_DIR:STATIC=/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3 + + +######################## +# INTERNAL cache entries +######################## + +//ADVANCED property for variable: CMAKE_AR +CMAKE_AR-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_BUILD_TOOL +CMAKE_BUILD_TOOL-ADVANCED:INTERNAL=1 +//What is the target build tool cmake is generating for. +CMAKE_BUILD_TOOL:INTERNAL=/usr/bin/make +//This is the directory where this CMakeCache.txt was created +CMAKE_CACHEFILE_DIR:INTERNAL=/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build +//Major version of cmake used to create the current loaded cache +CMAKE_CACHE_MAJOR_VERSION:INTERNAL=2 +//Minor version of cmake used to create the current loaded cache +CMAKE_CACHE_MINOR_VERSION:INTERNAL=8 +//Patch version of cmake used to create the current loaded cache +CMAKE_CACHE_PATCH_VERSION:INTERNAL=12 +//ADVANCED property for variable: CMAKE_COLOR_MAKEFILE +CMAKE_COLOR_MAKEFILE-ADVANCED:INTERNAL=1 +//Path to CMake executable. +CMAKE_COMMAND:INTERNAL=/usr/bin/cmake +//Path to cpack program executable. +CMAKE_CPACK_COMMAND:INTERNAL=/usr/bin/cpack +//Path to ctest program executable. +CMAKE_CTEST_COMMAND:INTERNAL=/usr/bin/ctest +//ADVANCED property for variable: CMAKE_CXX_COMPILER +CMAKE_CXX_COMPILER-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS +CMAKE_CXX_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_DEBUG +CMAKE_CXX_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_MINSIZEREL +CMAKE_CXX_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_RELEASE +CMAKE_CXX_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_RELWITHDEBINFO +CMAKE_CXX_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_COMPILER +CMAKE_C_COMPILER-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS +CMAKE_C_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS_DEBUG +CMAKE_C_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS_MINSIZEREL +CMAKE_C_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS_RELEASE +CMAKE_C_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS_RELWITHDEBINFO +CMAKE_C_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//Executable file format +CMAKE_EXECUTABLE_FORMAT:INTERNAL=ELF +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS +CMAKE_EXE_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_DEBUG +CMAKE_EXE_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_MINSIZEREL +CMAKE_EXE_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_RELEASE +CMAKE_EXE_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXPORT_COMPILE_COMMANDS +CMAKE_EXPORT_COMPILE_COMMANDS-ADVANCED:INTERNAL=1 +//Name of generator. +CMAKE_GENERATOR:INTERNAL=Unix Makefiles +//Name of generator toolset. +CMAKE_GENERATOR_TOOLSET:INTERNAL= +//Start directory with the top level CMakeLists.txt file for this +// project +CMAKE_HOME_DIRECTORY:INTERNAL=/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3 +//Install .so files without execute permission. +CMAKE_INSTALL_SO_NO_EXE:INTERNAL=1 +//ADVANCED property for variable: CMAKE_LINKER +CMAKE_LINKER-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MAKE_PROGRAM +CMAKE_MAKE_PROGRAM-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS +CMAKE_MODULE_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_DEBUG +CMAKE_MODULE_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL +CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_RELEASE +CMAKE_MODULE_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_NM +CMAKE_NM-ADVANCED:INTERNAL=1 +//number of local generators +CMAKE_NUMBER_OF_LOCAL_GENERATORS:INTERNAL=3 +//ADVANCED property for variable: CMAKE_OBJCOPY +CMAKE_OBJCOPY-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_OBJDUMP +CMAKE_OBJDUMP-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_RANLIB +CMAKE_RANLIB-ADVANCED:INTERNAL=1 +//Path to CMake installation. +CMAKE_ROOT:INTERNAL=/usr/share/cmake-2.8 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS +CMAKE_SHARED_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_DEBUG +CMAKE_SHARED_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL +CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_RELEASE +CMAKE_SHARED_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SKIP_INSTALL_RPATH +CMAKE_SKIP_INSTALL_RPATH-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SKIP_RPATH +CMAKE_SKIP_RPATH-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS +CMAKE_STATIC_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_DEBUG +CMAKE_STATIC_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL +CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_RELEASE +CMAKE_STATIC_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STRIP +CMAKE_STRIP-ADVANCED:INTERNAL=1 +//uname command +CMAKE_UNAME:INTERNAL=/bin/uname +//ADVANCED property for variable: CMAKE_USE_RELATIVE_PATHS +CMAKE_USE_RELATIVE_PATHS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_VERBOSE_MAKEFILE +CMAKE_VERBOSE_MAKEFILE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: OpenCV_3RDPARTY_LIB_DIR_DBG +OpenCV_3RDPARTY_LIB_DIR_DBG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: OpenCV_3RDPARTY_LIB_DIR_OPT +OpenCV_3RDPARTY_LIB_DIR_OPT-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: OpenCV_CONFIG_PATH +OpenCV_CONFIG_PATH-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: OpenCV_LIB_DIR_DBG +OpenCV_LIB_DIR_DBG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: OpenCV_LIB_DIR_OPT +OpenCV_LIB_DIR_OPT-ADVANCED:INTERNAL=1 + diff --git a/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CMakeCCompiler.cmake b/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CMakeCCompiler.cmake new file mode 100644 index 00000000..f4a508be --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CMakeCCompiler.cmake @@ -0,0 +1,56 @@ +set(CMAKE_C_COMPILER "/usr/bin/cc") +set(CMAKE_C_COMPILER_ARG1 "") +set(CMAKE_C_COMPILER_ID "GNU") +set(CMAKE_C_COMPILER_VERSION "4.8.4") +set(CMAKE_C_PLATFORM_ID "Linux") + +set(CMAKE_AR "/usr/bin/ar") +set(CMAKE_RANLIB "/usr/bin/ranlib") +set(CMAKE_LINKER "/usr/bin/ld") +set(CMAKE_COMPILER_IS_GNUCC 1) +set(CMAKE_C_COMPILER_LOADED 1) +set(CMAKE_C_COMPILER_WORKS TRUE) +set(CMAKE_C_ABI_COMPILED TRUE) +set(CMAKE_COMPILER_IS_MINGW ) +set(CMAKE_COMPILER_IS_CYGWIN ) +if(CMAKE_COMPILER_IS_CYGWIN) + set(CYGWIN 1) + set(UNIX 1) +endif() + +set(CMAKE_C_COMPILER_ENV_VAR "CC") + +if(CMAKE_COMPILER_IS_MINGW) + set(MINGW 1) +endif() +set(CMAKE_C_COMPILER_ID_RUN 1) +set(CMAKE_C_SOURCE_FILE_EXTENSIONS c) +set(CMAKE_C_IGNORE_EXTENSIONS h;H;o;O;obj;OBJ;def;DEF;rc;RC) +set(CMAKE_C_LINKER_PREFERENCE 10) + +# Save compiler ABI information. +set(CMAKE_C_SIZEOF_DATA_PTR "8") +set(CMAKE_C_COMPILER_ABI "ELF") +set(CMAKE_C_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") + +if(CMAKE_C_SIZEOF_DATA_PTR) + set(CMAKE_SIZEOF_VOID_P "${CMAKE_C_SIZEOF_DATA_PTR}") +endif() + +if(CMAKE_C_COMPILER_ABI) + set(CMAKE_INTERNAL_PLATFORM_ABI "${CMAKE_C_COMPILER_ABI}") +endif() + +if(CMAKE_C_LIBRARY_ARCHITECTURE) + set(CMAKE_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") +endif() + + + + +set(CMAKE_C_IMPLICIT_LINK_LIBRARIES "c") +set(CMAKE_C_IMPLICIT_LINK_DIRECTORIES "/usr/lib/gcc/x86_64-linux-gnu/4.8;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib") +set(CMAKE_C_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES "") + + + diff --git a/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake b/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake new file mode 100644 index 00000000..1ca40dbc --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake @@ -0,0 +1,57 @@ +set(CMAKE_CXX_COMPILER "/usr/bin/c++") +set(CMAKE_CXX_COMPILER_ARG1 "") +set(CMAKE_CXX_COMPILER_ID "GNU") +set(CMAKE_CXX_COMPILER_VERSION "4.8.4") +set(CMAKE_CXX_PLATFORM_ID "Linux") + +set(CMAKE_AR "/usr/bin/ar") +set(CMAKE_RANLIB "/usr/bin/ranlib") +set(CMAKE_LINKER "/usr/bin/ld") +set(CMAKE_COMPILER_IS_GNUCXX 1) +set(CMAKE_CXX_COMPILER_LOADED 1) +set(CMAKE_CXX_COMPILER_WORKS TRUE) +set(CMAKE_CXX_ABI_COMPILED TRUE) +set(CMAKE_COMPILER_IS_MINGW ) +set(CMAKE_COMPILER_IS_CYGWIN ) +if(CMAKE_COMPILER_IS_CYGWIN) + set(CYGWIN 1) + set(UNIX 1) +endif() + +set(CMAKE_CXX_COMPILER_ENV_VAR "CXX") + +if(CMAKE_COMPILER_IS_MINGW) + set(MINGW 1) +endif() +set(CMAKE_CXX_COMPILER_ID_RUN 1) +set(CMAKE_CXX_IGNORE_EXTENSIONS inl;h;hpp;HPP;H;o;O;obj;OBJ;def;DEF;rc;RC) +set(CMAKE_CXX_SOURCE_FILE_EXTENSIONS C;M;c++;cc;cpp;cxx;m;mm;CPP) +set(CMAKE_CXX_LINKER_PREFERENCE 30) +set(CMAKE_CXX_LINKER_PREFERENCE_PROPAGATES 1) + +# Save compiler ABI information. +set(CMAKE_CXX_SIZEOF_DATA_PTR "8") +set(CMAKE_CXX_COMPILER_ABI "ELF") +set(CMAKE_CXX_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") + +if(CMAKE_CXX_SIZEOF_DATA_PTR) + set(CMAKE_SIZEOF_VOID_P "${CMAKE_CXX_SIZEOF_DATA_PTR}") +endif() + +if(CMAKE_CXX_COMPILER_ABI) + set(CMAKE_INTERNAL_PLATFORM_ABI "${CMAKE_CXX_COMPILER_ABI}") +endif() + +if(CMAKE_CXX_LIBRARY_ARCHITECTURE) + set(CMAKE_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") +endif() + + + + +set(CMAKE_CXX_IMPLICIT_LINK_LIBRARIES "stdc++;m;c") +set(CMAKE_CXX_IMPLICIT_LINK_DIRECTORIES "/usr/lib/gcc/x86_64-linux-gnu/4.8;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib") +set(CMAKE_CXX_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES "") + + + diff --git a/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_C.bin b/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_C.bin new file mode 100755 index 00000000..f909aaac Binary files /dev/null and b/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_C.bin differ diff --git a/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_CXX.bin b/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_CXX.bin new file mode 100755 index 00000000..d6b41c89 Binary files /dev/null and b/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_CXX.bin differ diff --git a/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CMakeSystem.cmake b/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CMakeSystem.cmake new file mode 100644 index 00000000..8444407c --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CMakeSystem.cmake @@ -0,0 +1,15 @@ +set(CMAKE_HOST_SYSTEM "Linux-4.4.0-94-generic") +set(CMAKE_HOST_SYSTEM_NAME "Linux") +set(CMAKE_HOST_SYSTEM_VERSION "4.4.0-94-generic") +set(CMAKE_HOST_SYSTEM_PROCESSOR "x86_64") + + + +set(CMAKE_SYSTEM "Linux-4.4.0-94-generic") +set(CMAKE_SYSTEM_NAME "Linux") +set(CMAKE_SYSTEM_VERSION "4.4.0-94-generic") +set(CMAKE_SYSTEM_PROCESSOR "x86_64") + +set(CMAKE_CROSSCOMPILING "FALSE") + +set(CMAKE_SYSTEM_LOADED 1) diff --git a/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CompilerIdC/CMakeCCompilerId.c b/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CompilerIdC/CMakeCCompilerId.c new file mode 100644 index 00000000..cba81d4a --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CompilerIdC/CMakeCCompilerId.c @@ -0,0 +1,389 @@ +#ifdef __cplusplus +# error "A C++ compiler has been selected for C." +#endif + +/* Version number components: V=Version, R=Revision, P=Patch + Version date components: YYYY=Year, MM=Month, DD=Day */ + +#if defined(__18CXX) +# define ID_VOID_MAIN +#endif + +#if defined(__INTEL_COMPILER) || defined(__ICC) +# define COMPILER_ID "Intel" + /* __INTEL_COMPILER = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER/100) +# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER % 10) +# if defined(__INTEL_COMPILER_BUILD_DATE) + /* __INTEL_COMPILER_BUILD_DATE = YYYYMMDD */ +# define COMPILER_VERSION_TWEAK DEC(__INTEL_COMPILER_BUILD_DATE) +# endif + +#elif defined(__PATHCC__) +# define COMPILER_ID "PathScale" +# define COMPILER_VERSION_MAJOR DEC(__PATHCC__) +# define COMPILER_VERSION_MINOR DEC(__PATHCC_MINOR__) +# if defined(__PATHCC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__PATHCC_PATCHLEVEL__) +# endif + +#elif defined(__clang__) +# define COMPILER_ID "Clang" +# define COMPILER_VERSION_MAJOR DEC(__clang_major__) +# define COMPILER_VERSION_MINOR DEC(__clang_minor__) +# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__) + +#elif defined(__BORLANDC__) && defined(__CODEGEARC_VERSION__) +# define COMPILER_ID "Embarcadero" +# define COMPILER_VERSION_MAJOR HEX(__CODEGEARC_VERSION__>>24 & 0x00FF) +# define COMPILER_VERSION_MINOR HEX(__CODEGEARC_VERSION__>>16 & 0x00FF) +# define COMPILER_VERSION_PATCH HEX(__CODEGEARC_VERSION__ & 0xFFFF) + +#elif defined(__BORLANDC__) +# define COMPILER_ID "Borland" + /* __BORLANDC__ = 0xVRR */ +# define COMPILER_VERSION_MAJOR HEX(__BORLANDC__>>8) +# define COMPILER_VERSION_MINOR HEX(__BORLANDC__ & 0xFF) + +#elif defined(__WATCOMC__) +# define COMPILER_ID "Watcom" + /* __WATCOMC__ = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(__WATCOMC__ / 100) +# define COMPILER_VERSION_MINOR DEC(__WATCOMC__ % 100) + +#elif defined(__SUNPRO_C) +# define COMPILER_ID "SunPro" +# if __SUNPRO_C >= 0x5100 + /* __SUNPRO_C = 0xVRRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_C>>12) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_C>>4 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_C & 0xF) +# else + /* __SUNPRO_C = 0xVRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_C>>8) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_C>>4 & 0xF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_C & 0xF) +# endif + +#elif defined(__HP_cc) +# define COMPILER_ID "HP" + /* __HP_cc = VVRRPP */ +# define COMPILER_VERSION_MAJOR DEC(__HP_cc/10000) +# define COMPILER_VERSION_MINOR DEC(__HP_cc/100 % 100) +# define COMPILER_VERSION_PATCH DEC(__HP_cc % 100) + +#elif defined(__DECC) +# define COMPILER_ID "Compaq" + /* __DECC_VER = VVRRTPPPP */ +# define COMPILER_VERSION_MAJOR DEC(__DECC_VER/10000000) +# define COMPILER_VERSION_MINOR DEC(__DECC_VER/100000 % 100) +# define COMPILER_VERSION_PATCH DEC(__DECC_VER % 10000) + +#elif defined(__IBMC__) +# if defined(__COMPILER_VER__) +# define COMPILER_ID "zOS" +# else +# if __IBMC__ >= 800 +# define COMPILER_ID "XL" +# else +# define COMPILER_ID "VisualAge" +# endif + /* __IBMC__ = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__IBMC__/100) +# define COMPILER_VERSION_MINOR DEC(__IBMC__/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__IBMC__ % 10) +# endif + +#elif defined(__PGI) +# define COMPILER_ID "PGI" +# define COMPILER_VERSION_MAJOR DEC(__PGIC__) +# define COMPILER_VERSION_MINOR DEC(__PGIC_MINOR__) +# if defined(__PGIC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__PGIC_PATCHLEVEL__) +# endif + +#elif defined(_CRAYC) +# define COMPILER_ID "Cray" +# define COMPILER_VERSION_MAJOR DEC(_RELEASE) +# define COMPILER_VERSION_MINOR DEC(_RELEASE_MINOR) + +#elif defined(__TI_COMPILER_VERSION__) +# define COMPILER_ID "TI" + /* __TI_COMPILER_VERSION__ = VVVRRRPPP */ +# define COMPILER_VERSION_MAJOR DEC(__TI_COMPILER_VERSION__/1000000) +# define COMPILER_VERSION_MINOR DEC(__TI_COMPILER_VERSION__/1000 % 1000) +# define COMPILER_VERSION_PATCH DEC(__TI_COMPILER_VERSION__ % 1000) + +#elif defined(__TINYC__) +# define COMPILER_ID "TinyCC" + +#elif defined(__SCO_VERSION__) +# define COMPILER_ID "SCO" + +#elif defined(__GNUC__) +# define COMPILER_ID "GNU" +# define COMPILER_VERSION_MAJOR DEC(__GNUC__) +# define COMPILER_VERSION_MINOR DEC(__GNUC_MINOR__) +# if defined(__GNUC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__) +# endif + +#elif defined(_MSC_VER) +# define COMPILER_ID "MSVC" + /* _MSC_VER = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(_MSC_VER / 100) +# define COMPILER_VERSION_MINOR DEC(_MSC_VER % 100) +# if defined(_MSC_FULL_VER) +# if _MSC_VER >= 1400 + /* _MSC_FULL_VER = VVRRPPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 100000) +# else + /* _MSC_FULL_VER = VVRRPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 10000) +# endif +# endif +# if defined(_MSC_BUILD) +# define COMPILER_VERSION_TWEAK DEC(_MSC_BUILD) +# endif + +/* Analog VisualDSP++ >= 4.5.6 */ +#elif defined(__VISUALDSPVERSION__) +# define COMPILER_ID "ADSP" + /* __VISUALDSPVERSION__ = 0xVVRRPP00 */ +# define COMPILER_VERSION_MAJOR HEX(__VISUALDSPVERSION__>>24) +# define COMPILER_VERSION_MINOR HEX(__VISUALDSPVERSION__>>16 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__VISUALDSPVERSION__>>8 & 0xFF) + +/* Analog VisualDSP++ < 4.5.6 */ +#elif defined(__ADSPBLACKFIN__) || defined(__ADSPTS__) || defined(__ADSP21000__) +# define COMPILER_ID "ADSP" + +/* IAR Systems compiler for embedded systems. + http://www.iar.com */ +#elif defined(__IAR_SYSTEMS_ICC__ ) || defined(__IAR_SYSTEMS_ICC) +# define COMPILER_ID "IAR" + +/* sdcc, the small devices C compiler for embedded systems, + http://sdcc.sourceforge.net */ +#elif defined(SDCC) +# define COMPILER_ID "SDCC" + /* SDCC = VRP */ +# define COMPILER_VERSION_MAJOR DEC(SDCC/100) +# define COMPILER_VERSION_MINOR DEC(SDCC/10 % 10) +# define COMPILER_VERSION_PATCH DEC(SDCC % 10) + +#elif defined(_SGI_COMPILER_VERSION) || defined(_COMPILER_VERSION) +# define COMPILER_ID "MIPSpro" +# if defined(_SGI_COMPILER_VERSION) + /* _SGI_COMPILER_VERSION = VRP */ +# define COMPILER_VERSION_MAJOR DEC(_SGI_COMPILER_VERSION/100) +# define COMPILER_VERSION_MINOR DEC(_SGI_COMPILER_VERSION/10 % 10) +# define COMPILER_VERSION_PATCH DEC(_SGI_COMPILER_VERSION % 10) +# else + /* _COMPILER_VERSION = VRP */ +# define COMPILER_VERSION_MAJOR DEC(_COMPILER_VERSION/100) +# define COMPILER_VERSION_MINOR DEC(_COMPILER_VERSION/10 % 10) +# define COMPILER_VERSION_PATCH DEC(_COMPILER_VERSION % 10) +# endif + +/* This compiler is either not known or is too old to define an + identification macro. Try to identify the platform and guess that + it is the native compiler. */ +#elif defined(__sgi) +# define COMPILER_ID "MIPSpro" + +#elif defined(__hpux) || defined(__hpua) +# define COMPILER_ID "HP" + +#else /* unknown compiler */ +# define COMPILER_ID "" + +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_compiler = "INFO" ":" "compiler[" COMPILER_ID "]"; + +/* Identify known platforms by name. */ +#if defined(__linux) || defined(__linux__) || defined(linux) +# define PLATFORM_ID "Linux" + +#elif defined(__CYGWIN__) +# define PLATFORM_ID "Cygwin" + +#elif defined(__MINGW32__) +# define PLATFORM_ID "MinGW" + +#elif defined(__APPLE__) +# define PLATFORM_ID "Darwin" + +#elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32) +# define PLATFORM_ID "Windows" + +#elif defined(__FreeBSD__) || defined(__FreeBSD) +# define PLATFORM_ID "FreeBSD" + +#elif defined(__NetBSD__) || defined(__NetBSD) +# define PLATFORM_ID "NetBSD" + +#elif defined(__OpenBSD__) || defined(__OPENBSD) +# define PLATFORM_ID "OpenBSD" + +#elif defined(__sun) || defined(sun) +# define PLATFORM_ID "SunOS" + +#elif defined(_AIX) || defined(__AIX) || defined(__AIX__) || defined(__aix) || defined(__aix__) +# define PLATFORM_ID "AIX" + +#elif defined(__sgi) || defined(__sgi__) || defined(_SGI) +# define PLATFORM_ID "IRIX" + +#elif defined(__hpux) || defined(__hpux__) +# define PLATFORM_ID "HP-UX" + +#elif defined(__HAIKU__) +# define PLATFORM_ID "Haiku" + +#elif defined(__BeOS) || defined(__BEOS__) || defined(_BEOS) +# define PLATFORM_ID "BeOS" + +#elif defined(__QNX__) || defined(__QNXNTO__) +# define PLATFORM_ID "QNX" + +#elif defined(__tru64) || defined(_tru64) || defined(__TRU64__) +# define PLATFORM_ID "Tru64" + +#elif defined(__riscos) || defined(__riscos__) +# define PLATFORM_ID "RISCos" + +#elif defined(__sinix) || defined(__sinix__) || defined(__SINIX__) +# define PLATFORM_ID "SINIX" + +#elif defined(__UNIX_SV__) +# define PLATFORM_ID "UNIX_SV" + +#elif defined(__bsdos__) +# define PLATFORM_ID "BSDOS" + +#elif defined(_MPRAS) || defined(MPRAS) +# define PLATFORM_ID "MP-RAS" + +#elif defined(__osf) || defined(__osf__) +# define PLATFORM_ID "OSF1" + +#elif defined(_SCO_SV) || defined(SCO_SV) || defined(sco_sv) +# define PLATFORM_ID "SCO_SV" + +#elif defined(__ultrix) || defined(__ultrix__) || defined(_ULTRIX) +# define PLATFORM_ID "ULTRIX" + +#elif defined(__XENIX__) || defined(_XENIX) || defined(XENIX) +# define PLATFORM_ID "Xenix" + +#else /* unknown platform */ +# define PLATFORM_ID "" + +#endif + +/* For windows compilers MSVC and Intel we can determine + the architecture of the compiler being used. This is because + the compilers do not have flags that can change the architecture, + but rather depend on which compiler is being used +*/ +#if defined(_WIN32) && defined(_MSC_VER) +# if defined(_M_IA64) +# define ARCHITECTURE_ID "IA64" + +# elif defined(_M_X64) || defined(_M_AMD64) +# define ARCHITECTURE_ID "x64" + +# elif defined(_M_IX86) +# define ARCHITECTURE_ID "X86" + +# elif defined(_M_ARM) +# define ARCHITECTURE_ID "ARM" + +# elif defined(_M_MIPS) +# define ARCHITECTURE_ID "MIPS" + +# elif defined(_M_SH) +# define ARCHITECTURE_ID "SHx" + +# else /* unknown architecture */ +# define ARCHITECTURE_ID "" +# endif + +#else +# define ARCHITECTURE_ID "" +#endif + +/* Convert integer to decimal digit literals. */ +#define DEC(n) \ + ('0' + (((n) / 10000000)%10)), \ + ('0' + (((n) / 1000000)%10)), \ + ('0' + (((n) / 100000)%10)), \ + ('0' + (((n) / 10000)%10)), \ + ('0' + (((n) / 1000)%10)), \ + ('0' + (((n) / 100)%10)), \ + ('0' + (((n) / 10)%10)), \ + ('0' + ((n) % 10)) + +/* Convert integer to hex digit literals. */ +#define HEX(n) \ + ('0' + ((n)>>28 & 0xF)), \ + ('0' + ((n)>>24 & 0xF)), \ + ('0' + ((n)>>20 & 0xF)), \ + ('0' + ((n)>>16 & 0xF)), \ + ('0' + ((n)>>12 & 0xF)), \ + ('0' + ((n)>>8 & 0xF)), \ + ('0' + ((n)>>4 & 0xF)), \ + ('0' + ((n) & 0xF)) + +/* Construct a string literal encoding the version number components. */ +#ifdef COMPILER_VERSION_MAJOR +char const info_version[] = { + 'I', 'N', 'F', 'O', ':', + 'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','[', + COMPILER_VERSION_MAJOR, +# ifdef COMPILER_VERSION_MINOR + '.', COMPILER_VERSION_MINOR, +# ifdef COMPILER_VERSION_PATCH + '.', COMPILER_VERSION_PATCH, +# ifdef COMPILER_VERSION_TWEAK + '.', COMPILER_VERSION_TWEAK, +# endif +# endif +# endif + ']','\0'}; +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_platform = "INFO" ":" "platform[" PLATFORM_ID "]"; +char const* info_arch = "INFO" ":" "arch[" ARCHITECTURE_ID "]"; + + + +/*--------------------------------------------------------------------------*/ + +#ifdef ID_VOID_MAIN +void main() {} +#else +int main(int argc, char* argv[]) +{ + int require = 0; + require += info_compiler[argc]; + require += info_platform[argc]; + require += info_arch[argc]; +#ifdef COMPILER_VERSION_MAJOR + require += info_version[argc]; +#endif + (void)argv; + return require; +} +#endif diff --git a/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CompilerIdC/a.out b/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CompilerIdC/a.out new file mode 100755 index 00000000..49a5ca2e Binary files /dev/null and b/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CompilerIdC/a.out differ diff --git a/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CompilerIdCXX/CMakeCXXCompilerId.cpp b/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CompilerIdCXX/CMakeCXXCompilerId.cpp new file mode 100644 index 00000000..e8220b26 --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CompilerIdCXX/CMakeCXXCompilerId.cpp @@ -0,0 +1,377 @@ +/* This source file must have a .cpp extension so that all C++ compilers + recognize the extension without flags. Borland does not know .cxx for + example. */ +#ifndef __cplusplus +# error "A C compiler has been selected for C++." +#endif + +/* Version number components: V=Version, R=Revision, P=Patch + Version date components: YYYY=Year, MM=Month, DD=Day */ + +#if defined(__COMO__) +# define COMPILER_ID "Comeau" + /* __COMO_VERSION__ = VRR */ +# define COMPILER_VERSION_MAJOR DEC(__COMO_VERSION__ / 100) +# define COMPILER_VERSION_MINOR DEC(__COMO_VERSION__ % 100) + +#elif defined(__INTEL_COMPILER) || defined(__ICC) +# define COMPILER_ID "Intel" + /* __INTEL_COMPILER = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER/100) +# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER % 10) +# if defined(__INTEL_COMPILER_BUILD_DATE) + /* __INTEL_COMPILER_BUILD_DATE = YYYYMMDD */ +# define COMPILER_VERSION_TWEAK DEC(__INTEL_COMPILER_BUILD_DATE) +# endif + +#elif defined(__PATHCC__) +# define COMPILER_ID "PathScale" +# define COMPILER_VERSION_MAJOR DEC(__PATHCC__) +# define COMPILER_VERSION_MINOR DEC(__PATHCC_MINOR__) +# if defined(__PATHCC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__PATHCC_PATCHLEVEL__) +# endif + +#elif defined(__clang__) +# define COMPILER_ID "Clang" +# define COMPILER_VERSION_MAJOR DEC(__clang_major__) +# define COMPILER_VERSION_MINOR DEC(__clang_minor__) +# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__) + +#elif defined(__BORLANDC__) && defined(__CODEGEARC_VERSION__) +# define COMPILER_ID "Embarcadero" +# define COMPILER_VERSION_MAJOR HEX(__CODEGEARC_VERSION__>>24 & 0x00FF) +# define COMPILER_VERSION_MINOR HEX(__CODEGEARC_VERSION__>>16 & 0x00FF) +# define COMPILER_VERSION_PATCH HEX(__CODEGEARC_VERSION__ & 0xFFFF) + +#elif defined(__BORLANDC__) +# define COMPILER_ID "Borland" + /* __BORLANDC__ = 0xVRR */ +# define COMPILER_VERSION_MAJOR HEX(__BORLANDC__>>8) +# define COMPILER_VERSION_MINOR HEX(__BORLANDC__ & 0xFF) + +#elif defined(__WATCOMC__) +# define COMPILER_ID "Watcom" + /* __WATCOMC__ = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(__WATCOMC__ / 100) +# define COMPILER_VERSION_MINOR DEC(__WATCOMC__ % 100) + +#elif defined(__SUNPRO_CC) +# define COMPILER_ID "SunPro" +# if __SUNPRO_CC >= 0x5100 + /* __SUNPRO_CC = 0xVRRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_CC>>12) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_CC>>4 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_CC & 0xF) +# else + /* __SUNPRO_CC = 0xVRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_CC>>8) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_CC>>4 & 0xF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_CC & 0xF) +# endif + +#elif defined(__HP_aCC) +# define COMPILER_ID "HP" + /* __HP_aCC = VVRRPP */ +# define COMPILER_VERSION_MAJOR DEC(__HP_aCC/10000) +# define COMPILER_VERSION_MINOR DEC(__HP_aCC/100 % 100) +# define COMPILER_VERSION_PATCH DEC(__HP_aCC % 100) + +#elif defined(__DECCXX) +# define COMPILER_ID "Compaq" + /* __DECCXX_VER = VVRRTPPPP */ +# define COMPILER_VERSION_MAJOR DEC(__DECCXX_VER/10000000) +# define COMPILER_VERSION_MINOR DEC(__DECCXX_VER/100000 % 100) +# define COMPILER_VERSION_PATCH DEC(__DECCXX_VER % 10000) + +#elif defined(__IBMCPP__) +# if defined(__COMPILER_VER__) +# define COMPILER_ID "zOS" +# else +# if __IBMCPP__ >= 800 +# define COMPILER_ID "XL" +# else +# define COMPILER_ID "VisualAge" +# endif + /* __IBMCPP__ = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__IBMCPP__/100) +# define COMPILER_VERSION_MINOR DEC(__IBMCPP__/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__IBMCPP__ % 10) +# endif + +#elif defined(__PGI) +# define COMPILER_ID "PGI" +# define COMPILER_VERSION_MAJOR DEC(__PGIC__) +# define COMPILER_VERSION_MINOR DEC(__PGIC_MINOR__) +# if defined(__PGIC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__PGIC_PATCHLEVEL__) +# endif + +#elif defined(_CRAYC) +# define COMPILER_ID "Cray" +# define COMPILER_VERSION_MAJOR DEC(_RELEASE) +# define COMPILER_VERSION_MINOR DEC(_RELEASE_MINOR) + +#elif defined(__TI_COMPILER_VERSION__) +# define COMPILER_ID "TI" + /* __TI_COMPILER_VERSION__ = VVVRRRPPP */ +# define COMPILER_VERSION_MAJOR DEC(__TI_COMPILER_VERSION__/1000000) +# define COMPILER_VERSION_MINOR DEC(__TI_COMPILER_VERSION__/1000 % 1000) +# define COMPILER_VERSION_PATCH DEC(__TI_COMPILER_VERSION__ % 1000) + +#elif defined(__SCO_VERSION__) +# define COMPILER_ID "SCO" + +#elif defined(__GNUC__) +# define COMPILER_ID "GNU" +# define COMPILER_VERSION_MAJOR DEC(__GNUC__) +# define COMPILER_VERSION_MINOR DEC(__GNUC_MINOR__) +# if defined(__GNUC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__) +# endif + +#elif defined(_MSC_VER) +# define COMPILER_ID "MSVC" + /* _MSC_VER = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(_MSC_VER / 100) +# define COMPILER_VERSION_MINOR DEC(_MSC_VER % 100) +# if defined(_MSC_FULL_VER) +# if _MSC_VER >= 1400 + /* _MSC_FULL_VER = VVRRPPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 100000) +# else + /* _MSC_FULL_VER = VVRRPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 10000) +# endif +# endif +# if defined(_MSC_BUILD) +# define COMPILER_VERSION_TWEAK DEC(_MSC_BUILD) +# endif + +/* Analog VisualDSP++ >= 4.5.6 */ +#elif defined(__VISUALDSPVERSION__) +# define COMPILER_ID "ADSP" + /* __VISUALDSPVERSION__ = 0xVVRRPP00 */ +# define COMPILER_VERSION_MAJOR HEX(__VISUALDSPVERSION__>>24) +# define COMPILER_VERSION_MINOR HEX(__VISUALDSPVERSION__>>16 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__VISUALDSPVERSION__>>8 & 0xFF) + +/* Analog VisualDSP++ < 4.5.6 */ +#elif defined(__ADSPBLACKFIN__) || defined(__ADSPTS__) || defined(__ADSP21000__) +# define COMPILER_ID "ADSP" + +/* IAR Systems compiler for embedded systems. + http://www.iar.com */ +#elif defined(__IAR_SYSTEMS_ICC__ ) || defined(__IAR_SYSTEMS_ICC) +# define COMPILER_ID "IAR" + +#elif defined(_SGI_COMPILER_VERSION) || defined(_COMPILER_VERSION) +# define COMPILER_ID "MIPSpro" +# if defined(_SGI_COMPILER_VERSION) + /* _SGI_COMPILER_VERSION = VRP */ +# define COMPILER_VERSION_MAJOR DEC(_SGI_COMPILER_VERSION/100) +# define COMPILER_VERSION_MINOR DEC(_SGI_COMPILER_VERSION/10 % 10) +# define COMPILER_VERSION_PATCH DEC(_SGI_COMPILER_VERSION % 10) +# else + /* _COMPILER_VERSION = VRP */ +# define COMPILER_VERSION_MAJOR DEC(_COMPILER_VERSION/100) +# define COMPILER_VERSION_MINOR DEC(_COMPILER_VERSION/10 % 10) +# define COMPILER_VERSION_PATCH DEC(_COMPILER_VERSION % 10) +# endif + +/* This compiler is either not known or is too old to define an + identification macro. Try to identify the platform and guess that + it is the native compiler. */ +#elif defined(__sgi) +# define COMPILER_ID "MIPSpro" + +#elif defined(__hpux) || defined(__hpua) +# define COMPILER_ID "HP" + +#else /* unknown compiler */ +# define COMPILER_ID "" + +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_compiler = "INFO" ":" "compiler[" COMPILER_ID "]"; + +/* Identify known platforms by name. */ +#if defined(__linux) || defined(__linux__) || defined(linux) +# define PLATFORM_ID "Linux" + +#elif defined(__CYGWIN__) +# define PLATFORM_ID "Cygwin" + +#elif defined(__MINGW32__) +# define PLATFORM_ID "MinGW" + +#elif defined(__APPLE__) +# define PLATFORM_ID "Darwin" + +#elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32) +# define PLATFORM_ID "Windows" + +#elif defined(__FreeBSD__) || defined(__FreeBSD) +# define PLATFORM_ID "FreeBSD" + +#elif defined(__NetBSD__) || defined(__NetBSD) +# define PLATFORM_ID "NetBSD" + +#elif defined(__OpenBSD__) || defined(__OPENBSD) +# define PLATFORM_ID "OpenBSD" + +#elif defined(__sun) || defined(sun) +# define PLATFORM_ID "SunOS" + +#elif defined(_AIX) || defined(__AIX) || defined(__AIX__) || defined(__aix) || defined(__aix__) +# define PLATFORM_ID "AIX" + +#elif defined(__sgi) || defined(__sgi__) || defined(_SGI) +# define PLATFORM_ID "IRIX" + +#elif defined(__hpux) || defined(__hpux__) +# define PLATFORM_ID "HP-UX" + +#elif defined(__HAIKU__) +# define PLATFORM_ID "Haiku" + +#elif defined(__BeOS) || defined(__BEOS__) || defined(_BEOS) +# define PLATFORM_ID "BeOS" + +#elif defined(__QNX__) || defined(__QNXNTO__) +# define PLATFORM_ID "QNX" + +#elif defined(__tru64) || defined(_tru64) || defined(__TRU64__) +# define PLATFORM_ID "Tru64" + +#elif defined(__riscos) || defined(__riscos__) +# define PLATFORM_ID "RISCos" + +#elif defined(__sinix) || defined(__sinix__) || defined(__SINIX__) +# define PLATFORM_ID "SINIX" + +#elif defined(__UNIX_SV__) +# define PLATFORM_ID "UNIX_SV" + +#elif defined(__bsdos__) +# define PLATFORM_ID "BSDOS" + +#elif defined(_MPRAS) || defined(MPRAS) +# define PLATFORM_ID "MP-RAS" + +#elif defined(__osf) || defined(__osf__) +# define PLATFORM_ID "OSF1" + +#elif defined(_SCO_SV) || defined(SCO_SV) || defined(sco_sv) +# define PLATFORM_ID "SCO_SV" + +#elif defined(__ultrix) || defined(__ultrix__) || defined(_ULTRIX) +# define PLATFORM_ID "ULTRIX" + +#elif defined(__XENIX__) || defined(_XENIX) || defined(XENIX) +# define PLATFORM_ID "Xenix" + +#else /* unknown platform */ +# define PLATFORM_ID "" + +#endif + +/* For windows compilers MSVC and Intel we can determine + the architecture of the compiler being used. This is because + the compilers do not have flags that can change the architecture, + but rather depend on which compiler is being used +*/ +#if defined(_WIN32) && defined(_MSC_VER) +# if defined(_M_IA64) +# define ARCHITECTURE_ID "IA64" + +# elif defined(_M_X64) || defined(_M_AMD64) +# define ARCHITECTURE_ID "x64" + +# elif defined(_M_IX86) +# define ARCHITECTURE_ID "X86" + +# elif defined(_M_ARM) +# define ARCHITECTURE_ID "ARM" + +# elif defined(_M_MIPS) +# define ARCHITECTURE_ID "MIPS" + +# elif defined(_M_SH) +# define ARCHITECTURE_ID "SHx" + +# else /* unknown architecture */ +# define ARCHITECTURE_ID "" +# endif + +#else +# define ARCHITECTURE_ID "" +#endif + +/* Convert integer to decimal digit literals. */ +#define DEC(n) \ + ('0' + (((n) / 10000000)%10)), \ + ('0' + (((n) / 1000000)%10)), \ + ('0' + (((n) / 100000)%10)), \ + ('0' + (((n) / 10000)%10)), \ + ('0' + (((n) / 1000)%10)), \ + ('0' + (((n) / 100)%10)), \ + ('0' + (((n) / 10)%10)), \ + ('0' + ((n) % 10)) + +/* Convert integer to hex digit literals. */ +#define HEX(n) \ + ('0' + ((n)>>28 & 0xF)), \ + ('0' + ((n)>>24 & 0xF)), \ + ('0' + ((n)>>20 & 0xF)), \ + ('0' + ((n)>>16 & 0xF)), \ + ('0' + ((n)>>12 & 0xF)), \ + ('0' + ((n)>>8 & 0xF)), \ + ('0' + ((n)>>4 & 0xF)), \ + ('0' + ((n) & 0xF)) + +/* Construct a string literal encoding the version number components. */ +#ifdef COMPILER_VERSION_MAJOR +char const info_version[] = { + 'I', 'N', 'F', 'O', ':', + 'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','[', + COMPILER_VERSION_MAJOR, +# ifdef COMPILER_VERSION_MINOR + '.', COMPILER_VERSION_MINOR, +# ifdef COMPILER_VERSION_PATCH + '.', COMPILER_VERSION_PATCH, +# ifdef COMPILER_VERSION_TWEAK + '.', COMPILER_VERSION_TWEAK, +# endif +# endif +# endif + ']','\0'}; +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_platform = "INFO" ":" "platform[" PLATFORM_ID "]"; +char const* info_arch = "INFO" ":" "arch[" ARCHITECTURE_ID "]"; + + + +/*--------------------------------------------------------------------------*/ + +int main(int argc, char* argv[]) +{ + int require = 0; + require += info_compiler[argc]; + require += info_platform[argc]; +#ifdef COMPILER_VERSION_MAJOR + require += info_version[argc]; +#endif + (void)argv; + return require; +} diff --git a/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CompilerIdCXX/a.out b/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CompilerIdCXX/a.out new file mode 100755 index 00000000..96c16077 Binary files /dev/null and b/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CompilerIdCXX/a.out differ diff --git a/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeDirectoryInformation.cmake b/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeDirectoryInformation.cmake new file mode 100644 index 00000000..6db047a0 --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeDirectoryInformation.cmake @@ -0,0 +1,16 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Relative path conversion top directories. +SET(CMAKE_RELATIVE_PATH_TOP_SOURCE "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3") +SET(CMAKE_RELATIVE_PATH_TOP_BINARY "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build") + +# Force unix paths in dependencies. +SET(CMAKE_FORCE_UNIX_PATHS 1) + + +# The C and CXX include file regular expressions for this directory. +SET(CMAKE_C_INCLUDE_REGEX_SCAN "^.*$") +SET(CMAKE_C_INCLUDE_REGEX_COMPLAIN "^$") +SET(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN}) +SET(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN}) diff --git a/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeOutput.log b/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeOutput.log new file mode 100644 index 00000000..3d4a2e05 --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeOutput.log @@ -0,0 +1,263 @@ +The system is: Linux - 4.4.0-94-generic - x86_64 +Compiling the C compiler identification source file "CMakeCCompilerId.c" succeeded. +Compiler: /usr/bin/cc +Build flags: +Id flags: + +The output was: +0 + + +Compilation of the C compiler identification source "CMakeCCompilerId.c" produced "a.out" + +The C compiler identification is GNU, found in "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CompilerIdC/a.out" + +Compiling the CXX compiler identification source file "CMakeCXXCompilerId.cpp" succeeded. +Compiler: /usr/bin/c++ +Build flags: +Id flags: + +The output was: +0 + + +Compilation of the CXX compiler identification source "CMakeCXXCompilerId.cpp" produced "a.out" + +The CXX compiler identification is GNU, found in "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles/2.8.12.2/CompilerIdCXX/a.out" + +Determining if the C compiler works passed with the following output: +Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeTmp + +Run Build Command:/usr/bin/make "cmTryCompileExec931520029/fast" +/usr/bin/make -f CMakeFiles/cmTryCompileExec931520029.dir/build.make CMakeFiles/cmTryCompileExec931520029.dir/build +make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeTmp' +/usr/bin/cmake -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeTmp/CMakeFiles" 1 +Building C object CMakeFiles/cmTryCompileExec931520029.dir/testCCompiler.c.o +/usr/bin/cc -o CMakeFiles/cmTryCompileExec931520029.dir/testCCompiler.c.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeTmp/testCCompiler.c" +Linking C executable cmTryCompileExec931520029 +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec931520029.dir/link.txt --verbose=1 +/usr/bin/cc CMakeFiles/cmTryCompileExec931520029.dir/testCCompiler.c.o -o cmTryCompileExec931520029 -rdynamic +make[1]: Leaving directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeTmp' + + +Detecting C compiler ABI info compiled with the following output: +Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeTmp + +Run Build Command:/usr/bin/make "cmTryCompileExec2586817804/fast" +/usr/bin/make -f CMakeFiles/cmTryCompileExec2586817804.dir/build.make CMakeFiles/cmTryCompileExec2586817804.dir/build +make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeTmp' +/usr/bin/cmake -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeTmp/CMakeFiles" 1 +Building C object CMakeFiles/cmTryCompileExec2586817804.dir/CMakeCCompilerABI.c.o +/usr/bin/cc -o CMakeFiles/cmTryCompileExec2586817804.dir/CMakeCCompilerABI.c.o -c /usr/share/cmake-2.8/Modules/CMakeCCompilerABI.c +Linking C executable cmTryCompileExec2586817804 +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec2586817804.dir/link.txt --verbose=1 +/usr/bin/cc -v CMakeFiles/cmTryCompileExec2586817804.dir/CMakeCCompilerABI.c.o -o cmTryCompileExec2586817804 -rdynamic +Using built-in specs. +COLLECT_GCC=/usr/bin/cc +COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/4.8/lto-wrapper +Target: x86_64-linux-gnu +Configured with: ../src/configure -v --with-pkgversion='Ubuntu 4.8.4-2ubuntu1~14.04.3' --with-bugurl=file:///usr/share/doc/gcc-4.8/README.Bugs --enable-languages=c,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-4.8 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --with-gxx-include-dir=/usr/include/c++/4.8 --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --enable-gnu-unique-object --disable-libmudflap --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-4.8-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu +Thread model: posix +gcc version 4.8.4 (Ubuntu 4.8.4-2ubuntu1~14.04.3) +COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/ +LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../:/lib/:/usr/lib/ +COLLECT_GCC_OPTIONS='-v' '-o' 'cmTryCompileExec2586817804' '-rdynamic' '-mtune=generic' '-march=x86-64' + /usr/lib/gcc/x86_64-linux-gnu/4.8/collect2 --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTryCompileExec2586817804 /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/4.8 -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../.. CMakeFiles/cmTryCompileExec2586817804.dir/CMakeCCompilerABI.c.o -lgcc --as-needed -lgcc_s --no-as-needed -lc -lgcc --as-needed -lgcc_s --no-as-needed /usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o +make[1]: Leaving directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeTmp' + + +Parsed C implicit link information from above output: + link line regex: [^( *|.*[/\])(ld|([^/\]+-)?ld|collect2)[^/\]*( |$)] + ignore line: [Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeTmp] + ignore line: [] + ignore line: [Run Build Command:/usr/bin/make "cmTryCompileExec2586817804/fast"] + ignore line: [/usr/bin/make -f CMakeFiles/cmTryCompileExec2586817804.dir/build.make CMakeFiles/cmTryCompileExec2586817804.dir/build] + ignore line: [make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeTmp'] + ignore line: [/usr/bin/cmake -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeTmp/CMakeFiles" 1] + ignore line: [Building C object CMakeFiles/cmTryCompileExec2586817804.dir/CMakeCCompilerABI.c.o] + ignore line: [/usr/bin/cc -o CMakeFiles/cmTryCompileExec2586817804.dir/CMakeCCompilerABI.c.o -c /usr/share/cmake-2.8/Modules/CMakeCCompilerABI.c] + ignore line: [Linking C executable cmTryCompileExec2586817804] + ignore line: [/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec2586817804.dir/link.txt --verbose=1] + ignore line: [/usr/bin/cc -v CMakeFiles/cmTryCompileExec2586817804.dir/CMakeCCompilerABI.c.o -o cmTryCompileExec2586817804 -rdynamic ] + ignore line: [Using built-in specs.] + ignore line: [COLLECT_GCC=/usr/bin/cc] + ignore line: [COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/4.8/lto-wrapper] + ignore line: [Target: x86_64-linux-gnu] + ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 4.8.4-2ubuntu1~14.04.3' --with-bugurl=file:///usr/share/doc/gcc-4.8/README.Bugs --enable-languages=c,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-4.8 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --with-gxx-include-dir=/usr/include/c++/4.8 --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --enable-gnu-unique-object --disable-libmudflap --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-4.8-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu] + ignore line: [Thread model: posix] + ignore line: [gcc version 4.8.4 (Ubuntu 4.8.4-2ubuntu1~14.04.3) ] + ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/] + ignore line: [LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../:/lib/:/usr/lib/] + ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'cmTryCompileExec2586817804' '-rdynamic' '-mtune=generic' '-march=x86-64'] + link line: [ /usr/lib/gcc/x86_64-linux-gnu/4.8/collect2 --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTryCompileExec2586817804 /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/4.8 -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../.. CMakeFiles/cmTryCompileExec2586817804.dir/CMakeCCompilerABI.c.o -lgcc --as-needed -lgcc_s --no-as-needed -lc -lgcc --as-needed -lgcc_s --no-as-needed /usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o] + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/collect2] ==> ignore + arg [--sysroot=/] ==> ignore + arg [--build-id] ==> ignore + arg [--eh-frame-hdr] ==> ignore + arg [-m] ==> ignore + arg [elf_x86_64] ==> ignore + arg [--hash-style=gnu] ==> ignore + arg [--as-needed] ==> ignore + arg [-export-dynamic] ==> ignore + arg [-dynamic-linker] ==> ignore + arg [/lib64/ld-linux-x86-64.so.2] ==> ignore + arg [-zrelro] ==> ignore + arg [-o] ==> ignore + arg [cmTryCompileExec2586817804] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o] ==> ignore + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] + arg [-L/lib/x86_64-linux-gnu] ==> dir [/lib/x86_64-linux-gnu] + arg [-L/lib/../lib] ==> dir [/lib/../lib] + arg [-L/usr/lib/x86_64-linux-gnu] ==> dir [/usr/lib/x86_64-linux-gnu] + arg [-L/usr/lib/../lib] ==> dir [/usr/lib/../lib] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] + arg [CMakeFiles/cmTryCompileExec2586817804.dir/CMakeCCompilerABI.c.o] ==> ignore + arg [-lgcc] ==> lib [gcc] + arg [--as-needed] ==> ignore + arg [-lgcc_s] ==> lib [gcc_s] + arg [--no-as-needed] ==> ignore + arg [-lc] ==> lib [c] + arg [-lgcc] ==> lib [gcc] + arg [--as-needed] ==> ignore + arg [-lgcc_s] ==> lib [gcc_s] + arg [--no-as-needed] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o] ==> ignore + remove lib [gcc] + remove lib [gcc_s] + remove lib [gcc] + remove lib [gcc_s] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8] ==> [/usr/lib/gcc/x86_64-linux-gnu/4.8] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] ==> [/usr/lib] + collapse library dir [/lib/x86_64-linux-gnu] ==> [/lib/x86_64-linux-gnu] + collapse library dir [/lib/../lib] ==> [/lib] + collapse library dir [/usr/lib/x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/../lib] ==> [/usr/lib] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] ==> [/usr/lib] + implicit libs: [c] + implicit dirs: [/usr/lib/gcc/x86_64-linux-gnu/4.8;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib] + implicit fwks: [] + + +Determining if the CXX compiler works passed with the following output: +Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeTmp + +Run Build Command:/usr/bin/make "cmTryCompileExec4290537632/fast" +/usr/bin/make -f CMakeFiles/cmTryCompileExec4290537632.dir/build.make CMakeFiles/cmTryCompileExec4290537632.dir/build +make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeTmp' +/usr/bin/cmake -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeTmp/CMakeFiles" 1 +Building CXX object CMakeFiles/cmTryCompileExec4290537632.dir/testCXXCompiler.cxx.o +/usr/bin/c++ -o CMakeFiles/cmTryCompileExec4290537632.dir/testCXXCompiler.cxx.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeTmp/testCXXCompiler.cxx" +Linking CXX executable cmTryCompileExec4290537632 +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec4290537632.dir/link.txt --verbose=1 +/usr/bin/c++ CMakeFiles/cmTryCompileExec4290537632.dir/testCXXCompiler.cxx.o -o cmTryCompileExec4290537632 -rdynamic +make[1]: Leaving directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeTmp' + + +Detecting CXX compiler ABI info compiled with the following output: +Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeTmp + +Run Build Command:/usr/bin/make "cmTryCompileExec549110161/fast" +/usr/bin/make -f CMakeFiles/cmTryCompileExec549110161.dir/build.make CMakeFiles/cmTryCompileExec549110161.dir/build +make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeTmp' +/usr/bin/cmake -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeTmp/CMakeFiles" 1 +Building CXX object CMakeFiles/cmTryCompileExec549110161.dir/CMakeCXXCompilerABI.cpp.o +/usr/bin/c++ -o CMakeFiles/cmTryCompileExec549110161.dir/CMakeCXXCompilerABI.cpp.o -c /usr/share/cmake-2.8/Modules/CMakeCXXCompilerABI.cpp +Linking CXX executable cmTryCompileExec549110161 +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec549110161.dir/link.txt --verbose=1 +/usr/bin/c++ -v CMakeFiles/cmTryCompileExec549110161.dir/CMakeCXXCompilerABI.cpp.o -o cmTryCompileExec549110161 -rdynamic +Using built-in specs. +COLLECT_GCC=/usr/bin/c++ +COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/4.8/lto-wrapper +Target: x86_64-linux-gnu +Configured with: ../src/configure -v --with-pkgversion='Ubuntu 4.8.4-2ubuntu1~14.04.3' --with-bugurl=file:///usr/share/doc/gcc-4.8/README.Bugs --enable-languages=c,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-4.8 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --with-gxx-include-dir=/usr/include/c++/4.8 --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --enable-gnu-unique-object --disable-libmudflap --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-4.8-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu +Thread model: posix +gcc version 4.8.4 (Ubuntu 4.8.4-2ubuntu1~14.04.3) +COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/ +LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../:/lib/:/usr/lib/ +COLLECT_GCC_OPTIONS='-v' '-o' 'cmTryCompileExec549110161' '-rdynamic' '-shared-libgcc' '-mtune=generic' '-march=x86-64' + /usr/lib/gcc/x86_64-linux-gnu/4.8/collect2 --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTryCompileExec549110161 /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/4.8 -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../.. CMakeFiles/cmTryCompileExec549110161.dir/CMakeCXXCompilerABI.cpp.o -lstdc++ -lm -lgcc_s -lgcc -lc -lgcc_s -lgcc /usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o +make[1]: Leaving directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeTmp' + + +Parsed CXX implicit link information from above output: + link line regex: [^( *|.*[/\])(ld|([^/\]+-)?ld|collect2)[^/\]*( |$)] + ignore line: [Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeTmp] + ignore line: [] + ignore line: [Run Build Command:/usr/bin/make "cmTryCompileExec549110161/fast"] + ignore line: [/usr/bin/make -f CMakeFiles/cmTryCompileExec549110161.dir/build.make CMakeFiles/cmTryCompileExec549110161.dir/build] + ignore line: [make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeTmp'] + ignore line: [/usr/bin/cmake -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles/CMakeTmp/CMakeFiles" 1] + ignore line: [Building CXX object CMakeFiles/cmTryCompileExec549110161.dir/CMakeCXXCompilerABI.cpp.o] + ignore line: [/usr/bin/c++ -o CMakeFiles/cmTryCompileExec549110161.dir/CMakeCXXCompilerABI.cpp.o -c /usr/share/cmake-2.8/Modules/CMakeCXXCompilerABI.cpp] + ignore line: [Linking CXX executable cmTryCompileExec549110161] + ignore line: [/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec549110161.dir/link.txt --verbose=1] + ignore line: [/usr/bin/c++ -v CMakeFiles/cmTryCompileExec549110161.dir/CMakeCXXCompilerABI.cpp.o -o cmTryCompileExec549110161 -rdynamic ] + ignore line: [Using built-in specs.] + ignore line: [COLLECT_GCC=/usr/bin/c++] + ignore line: [COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/4.8/lto-wrapper] + ignore line: [Target: x86_64-linux-gnu] + ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 4.8.4-2ubuntu1~14.04.3' --with-bugurl=file:///usr/share/doc/gcc-4.8/README.Bugs --enable-languages=c,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-4.8 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --with-gxx-include-dir=/usr/include/c++/4.8 --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --enable-gnu-unique-object --disable-libmudflap --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-4.8-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu] + ignore line: [Thread model: posix] + ignore line: [gcc version 4.8.4 (Ubuntu 4.8.4-2ubuntu1~14.04.3) ] + ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/] + ignore line: [LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../:/lib/:/usr/lib/] + ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'cmTryCompileExec549110161' '-rdynamic' '-shared-libgcc' '-mtune=generic' '-march=x86-64'] + link line: [ /usr/lib/gcc/x86_64-linux-gnu/4.8/collect2 --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTryCompileExec549110161 /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/4.8 -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../.. CMakeFiles/cmTryCompileExec549110161.dir/CMakeCXXCompilerABI.cpp.o -lstdc++ -lm -lgcc_s -lgcc -lc -lgcc_s -lgcc /usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o] + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/collect2] ==> ignore + arg [--sysroot=/] ==> ignore + arg [--build-id] ==> ignore + arg [--eh-frame-hdr] ==> ignore + arg [-m] ==> ignore + arg [elf_x86_64] ==> ignore + arg [--hash-style=gnu] ==> ignore + arg [--as-needed] ==> ignore + arg [-export-dynamic] ==> ignore + arg [-dynamic-linker] ==> ignore + arg [/lib64/ld-linux-x86-64.so.2] ==> ignore + arg [-zrelro] ==> ignore + arg [-o] ==> ignore + arg [cmTryCompileExec549110161] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o] ==> ignore + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] + arg [-L/lib/x86_64-linux-gnu] ==> dir [/lib/x86_64-linux-gnu] + arg [-L/lib/../lib] ==> dir [/lib/../lib] + arg [-L/usr/lib/x86_64-linux-gnu] ==> dir [/usr/lib/x86_64-linux-gnu] + arg [-L/usr/lib/../lib] ==> dir [/usr/lib/../lib] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] + arg [CMakeFiles/cmTryCompileExec549110161.dir/CMakeCXXCompilerABI.cpp.o] ==> ignore + arg [-lstdc++] ==> lib [stdc++] + arg [-lm] ==> lib [m] + arg [-lgcc_s] ==> lib [gcc_s] + arg [-lgcc] ==> lib [gcc] + arg [-lc] ==> lib [c] + arg [-lgcc_s] ==> lib [gcc_s] + arg [-lgcc] ==> lib [gcc] + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o] ==> ignore + remove lib [gcc_s] + remove lib [gcc] + remove lib [gcc_s] + remove lib [gcc] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8] ==> [/usr/lib/gcc/x86_64-linux-gnu/4.8] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] ==> [/usr/lib] + collapse library dir [/lib/x86_64-linux-gnu] ==> [/lib/x86_64-linux-gnu] + collapse library dir [/lib/../lib] ==> [/lib] + collapse library dir [/usr/lib/x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/../lib] ==> [/usr/lib] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] ==> [/usr/lib] + implicit libs: [stdc++;m;c] + implicit dirs: [/usr/lib/gcc/x86_64-linux-gnu/4.8;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib] + implicit fwks: [] + + diff --git a/vSLAM/ch9 project/0.3/build/CMakeFiles/Makefile.cmake b/vSLAM/ch9 project/0.3/build/CMakeFiles/Makefile.cmake new file mode 100644 index 00000000..241b57e2 --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/CMakeFiles/Makefile.cmake @@ -0,0 +1,79 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# The generator used is: +SET(CMAKE_DEPENDS_GENERATOR "Unix Makefiles") + +# The top level Makefile was generated from the following files: +SET(CMAKE_MAKEFILE_DEPENDS + "CMakeCache.txt" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build/SophusConfig.cmake" + "../CMakeLists.txt" + "CMakeFiles/2.8.12.2/CMakeCCompiler.cmake" + "CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake" + "CMakeFiles/2.8.12.2/CMakeSystem.cmake" + "../cmake_modules/FindG2O.cmake" + "../src/CMakeLists.txt" + "../test/CMakeLists.txt" + "/usr/local/share/OpenCV/OpenCVConfig-version.cmake" + "/usr/local/share/OpenCV/OpenCVConfig.cmake" + "/usr/local/share/OpenCV/OpenCVModules-release.cmake" + "/usr/local/share/OpenCV/OpenCVModules.cmake" + "/usr/share/cmake-2.8/Modules/CMakeCCompiler.cmake.in" + "/usr/share/cmake-2.8/Modules/CMakeCCompilerABI.c" + "/usr/share/cmake-2.8/Modules/CMakeCInformation.cmake" + "/usr/share/cmake-2.8/Modules/CMakeCXXCompiler.cmake.in" + "/usr/share/cmake-2.8/Modules/CMakeCXXCompilerABI.cpp" + "/usr/share/cmake-2.8/Modules/CMakeCXXInformation.cmake" + "/usr/share/cmake-2.8/Modules/CMakeClDeps.cmake" + "/usr/share/cmake-2.8/Modules/CMakeCommonLanguageInclude.cmake" + "/usr/share/cmake-2.8/Modules/CMakeDetermineCCompiler.cmake" + "/usr/share/cmake-2.8/Modules/CMakeDetermineCXXCompiler.cmake" + "/usr/share/cmake-2.8/Modules/CMakeDetermineCompiler.cmake" + "/usr/share/cmake-2.8/Modules/CMakeDetermineCompilerABI.cmake" + "/usr/share/cmake-2.8/Modules/CMakeDetermineCompilerId.cmake" + "/usr/share/cmake-2.8/Modules/CMakeDetermineSystem.cmake" + "/usr/share/cmake-2.8/Modules/CMakeFindBinUtils.cmake" + "/usr/share/cmake-2.8/Modules/CMakeGenericSystem.cmake" + "/usr/share/cmake-2.8/Modules/CMakeParseImplicitLinkInfo.cmake" + "/usr/share/cmake-2.8/Modules/CMakeSystem.cmake.in" + "/usr/share/cmake-2.8/Modules/CMakeSystemSpecificInformation.cmake" + "/usr/share/cmake-2.8/Modules/CMakeTestCCompiler.cmake" + "/usr/share/cmake-2.8/Modules/CMakeTestCXXCompiler.cmake" + "/usr/share/cmake-2.8/Modules/CMakeTestCompilerCommon.cmake" + "/usr/share/cmake-2.8/Modules/CMakeUnixFindMake.cmake" + "/usr/share/cmake-2.8/Modules/Compiler/GNU-C.cmake" + "/usr/share/cmake-2.8/Modules/Compiler/GNU-CXX.cmake" + "/usr/share/cmake-2.8/Modules/Compiler/GNU.cmake" + "/usr/share/cmake-2.8/Modules/MultiArchCross.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux-CXX.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux-GNU-C.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux-GNU-CXX.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux-GNU.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux.cmake" + "/usr/share/cmake-2.8/Modules/Platform/UnixPaths.cmake" + ) + +# The corresponding makefile is: +SET(CMAKE_MAKEFILE_OUTPUTS + "Makefile" + "CMakeFiles/cmake.check_cache" + ) + +# Byproducts of CMake generate step: +SET(CMAKE_MAKEFILE_PRODUCTS + "CMakeFiles/2.8.12.2/CMakeSystem.cmake" + "CMakeFiles/2.8.12.2/CMakeCCompiler.cmake" + "CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake" + "CMakeFiles/2.8.12.2/CMakeCCompiler.cmake" + "CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake" + "CMakeFiles/CMakeDirectoryInformation.cmake" + "src/CMakeFiles/CMakeDirectoryInformation.cmake" + "test/CMakeFiles/CMakeDirectoryInformation.cmake" + ) + +# Dependency information for all targets: +SET(CMAKE_DEPEND_INFO_FILES + "src/CMakeFiles/myslam.dir/DependInfo.cmake" + "test/CMakeFiles/run_vo.dir/DependInfo.cmake" + ) diff --git a/vSLAM/ch9 project/0.3/build/CMakeFiles/Makefile2 b/vSLAM/ch9 project/0.3/build/CMakeFiles/Makefile2 new file mode 100644 index 00000000..7335acd0 --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/CMakeFiles/Makefile2 @@ -0,0 +1,164 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Default target executed when no arguments are given to make. +default_target: all +.PHONY : default_target + +# The main recursive all target +all: +.PHONY : all + +# The main recursive preinstall target +preinstall: +.PHONY : preinstall + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3" + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" + +#============================================================================= +# Directory level rules for directory src + +# Convenience name for "all" pass in the directory. +src/all: src/CMakeFiles/myslam.dir/all +.PHONY : src/all + +# Convenience name for "clean" pass in the directory. +src/clean: src/CMakeFiles/myslam.dir/clean +.PHONY : src/clean + +# Convenience name for "preinstall" pass in the directory. +src/preinstall: +.PHONY : src/preinstall + +#============================================================================= +# Target rules for target src/CMakeFiles/myslam.dir + +# All Build rule for target. +src/CMakeFiles/myslam.dir/all: + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/depend + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/build + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles" 1 2 3 4 5 6 7 + @echo "Built target myslam" +.PHONY : src/CMakeFiles/myslam.dir/all + +# Include target in all. +all: src/CMakeFiles/myslam.dir/all +.PHONY : all + +# Build rule for subdir invocation for target. +src/CMakeFiles/myslam.dir/rule: cmake_check_build_system + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles" 7 + $(MAKE) -f CMakeFiles/Makefile2 src/CMakeFiles/myslam.dir/all + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles" 0 +.PHONY : src/CMakeFiles/myslam.dir/rule + +# Convenience name for target. +myslam: src/CMakeFiles/myslam.dir/rule +.PHONY : myslam + +# clean rule for target. +src/CMakeFiles/myslam.dir/clean: + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/clean +.PHONY : src/CMakeFiles/myslam.dir/clean + +# clean rule for target. +clean: src/CMakeFiles/myslam.dir/clean +.PHONY : clean + +#============================================================================= +# Directory level rules for directory test + +# Convenience name for "all" pass in the directory. +test/all: test/CMakeFiles/run_vo.dir/all +.PHONY : test/all + +# Convenience name for "clean" pass in the directory. +test/clean: test/CMakeFiles/run_vo.dir/clean +.PHONY : test/clean + +# Convenience name for "preinstall" pass in the directory. +test/preinstall: +.PHONY : test/preinstall + +#============================================================================= +# Target rules for target test/CMakeFiles/run_vo.dir + +# All Build rule for target. +test/CMakeFiles/run_vo.dir/all: src/CMakeFiles/myslam.dir/all + $(MAKE) -f test/CMakeFiles/run_vo.dir/build.make test/CMakeFiles/run_vo.dir/depend + $(MAKE) -f test/CMakeFiles/run_vo.dir/build.make test/CMakeFiles/run_vo.dir/build + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles" 8 + @echo "Built target run_vo" +.PHONY : test/CMakeFiles/run_vo.dir/all + +# Include target in all. +all: test/CMakeFiles/run_vo.dir/all +.PHONY : all + +# Build rule for subdir invocation for target. +test/CMakeFiles/run_vo.dir/rule: cmake_check_build_system + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles" 8 + $(MAKE) -f CMakeFiles/Makefile2 test/CMakeFiles/run_vo.dir/all + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles" 0 +.PHONY : test/CMakeFiles/run_vo.dir/rule + +# Convenience name for target. +run_vo: test/CMakeFiles/run_vo.dir/rule +.PHONY : run_vo + +# clean rule for target. +test/CMakeFiles/run_vo.dir/clean: + $(MAKE) -f test/CMakeFiles/run_vo.dir/build.make test/CMakeFiles/run_vo.dir/clean +.PHONY : test/CMakeFiles/run_vo.dir/clean + +# clean rule for target. +clean: test/CMakeFiles/run_vo.dir/clean +.PHONY : clean + +#============================================================================= +# Special targets to cleanup operation of make. + +# Special rule to run CMake to check the build system integrity. +# No rule that depends on this can have commands that come from listfiles +# because they might be regenerated. +cmake_check_build_system: + $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0 +.PHONY : cmake_check_build_system + diff --git a/vSLAM/ch9 project/0.3/build/CMakeFiles/TargetDirectories.txt b/vSLAM/ch9 project/0.3/build/CMakeFiles/TargetDirectories.txt new file mode 100644 index 00000000..40876f26 --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/CMakeFiles/TargetDirectories.txt @@ -0,0 +1,2 @@ +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir diff --git a/vSLAM/ch9 project/0.3/build/CMakeFiles/cmake.check_cache b/vSLAM/ch9 project/0.3/build/CMakeFiles/cmake.check_cache new file mode 100644 index 00000000..3dccd731 --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/CMakeFiles/cmake.check_cache @@ -0,0 +1 @@ +# This file is generated by cmake for dependency checking of the CMakeCache.txt file diff --git a/vSLAM/ch9 project/0.3/build/CMakeFiles/progress.marks b/vSLAM/ch9 project/0.3/build/CMakeFiles/progress.marks new file mode 100644 index 00000000..45a4fb75 --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/CMakeFiles/progress.marks @@ -0,0 +1 @@ +8 diff --git a/vSLAM/ch9 project/0.3/build/Makefile b/vSLAM/ch9 project/0.3/build/Makefile new file mode 100644 index 00000000..b2fba7a0 --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/Makefile @@ -0,0 +1,150 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Default target executed when no arguments are given to make. +default_target: all +.PHONY : default_target + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3" + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" + +#============================================================================= +# Targets provided globally by CMake. + +# Special rule for the target edit_cache +edit_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running interactive CMake command-line interface..." + /usr/bin/cmake -i . +.PHONY : edit_cache + +# Special rule for the target edit_cache +edit_cache/fast: edit_cache +.PHONY : edit_cache/fast + +# Special rule for the target rebuild_cache +rebuild_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake to regenerate build system..." + /usr/bin/cmake -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) +.PHONY : rebuild_cache + +# Special rule for the target rebuild_cache +rebuild_cache/fast: rebuild_cache +.PHONY : rebuild_cache/fast + +# The main all target +all: cmake_check_build_system + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles/progress.marks" + $(MAKE) -f CMakeFiles/Makefile2 all + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles" 0 +.PHONY : all + +# The main clean target +clean: + $(MAKE) -f CMakeFiles/Makefile2 clean +.PHONY : clean + +# The main clean target +clean/fast: clean +.PHONY : clean/fast + +# Prepare targets for installation. +preinstall: all + $(MAKE) -f CMakeFiles/Makefile2 preinstall +.PHONY : preinstall + +# Prepare targets for installation. +preinstall/fast: + $(MAKE) -f CMakeFiles/Makefile2 preinstall +.PHONY : preinstall/fast + +# clear depends +depend: + $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 1 +.PHONY : depend + +#============================================================================= +# Target rules for targets named myslam + +# Build rule for target. +myslam: cmake_check_build_system + $(MAKE) -f CMakeFiles/Makefile2 myslam +.PHONY : myslam + +# fast build rule for target. +myslam/fast: + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/build +.PHONY : myslam/fast + +#============================================================================= +# Target rules for targets named run_vo + +# Build rule for target. +run_vo: cmake_check_build_system + $(MAKE) -f CMakeFiles/Makefile2 run_vo +.PHONY : run_vo + +# fast build rule for target. +run_vo/fast: + $(MAKE) -f test/CMakeFiles/run_vo.dir/build.make test/CMakeFiles/run_vo.dir/build +.PHONY : run_vo/fast + +# Help Target +help: + @echo "The following are some of the valid targets for this Makefile:" + @echo "... all (the default if no target is provided)" + @echo "... clean" + @echo "... depend" + @echo "... edit_cache" + @echo "... rebuild_cache" + @echo "... myslam" + @echo "... run_vo" +.PHONY : help + + + +#============================================================================= +# Special targets to cleanup operation of make. + +# Special rule to run CMake to check the build system integrity. +# No rule that depends on this can have commands that come from listfiles +# because they might be regenerated. +cmake_check_build_system: + $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0 +.PHONY : cmake_check_build_system + diff --git a/vSLAM/ch9 project/0.3/build/cmake_install.cmake b/vSLAM/ch9 project/0.3/build/cmake_install.cmake new file mode 100644 index 00000000..9a475e04 --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/cmake_install.cmake @@ -0,0 +1,51 @@ +# Install script for directory: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3 + +# Set the install prefix +IF(NOT DEFINED CMAKE_INSTALL_PREFIX) + SET(CMAKE_INSTALL_PREFIX "/usr/local") +ENDIF(NOT DEFINED CMAKE_INSTALL_PREFIX) +STRING(REGEX REPLACE "/$" "" CMAKE_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}") + +# Set the install configuration name. +IF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + IF(BUILD_TYPE) + STRING(REGEX REPLACE "^[^A-Za-z0-9_]+" "" + CMAKE_INSTALL_CONFIG_NAME "${BUILD_TYPE}") + ELSE(BUILD_TYPE) + SET(CMAKE_INSTALL_CONFIG_NAME "Release") + ENDIF(BUILD_TYPE) + MESSAGE(STATUS "Install configuration: \"${CMAKE_INSTALL_CONFIG_NAME}\"") +ENDIF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + +# Set the component getting installed. +IF(NOT CMAKE_INSTALL_COMPONENT) + IF(COMPONENT) + MESSAGE(STATUS "Install component: \"${COMPONENT}\"") + SET(CMAKE_INSTALL_COMPONENT "${COMPONENT}") + ELSE(COMPONENT) + SET(CMAKE_INSTALL_COMPONENT) + ENDIF(COMPONENT) +ENDIF(NOT CMAKE_INSTALL_COMPONENT) + +# Install shared libraries without execute permission? +IF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + SET(CMAKE_INSTALL_SO_NO_EXE "1") +ENDIF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + +IF(NOT CMAKE_INSTALL_LOCAL_ONLY) + # Include the install script for each subdirectory. + INCLUDE("/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src/cmake_install.cmake") + INCLUDE("/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/test/cmake_install.cmake") + +ENDIF(NOT CMAKE_INSTALL_LOCAL_ONLY) + +IF(CMAKE_INSTALL_COMPONENT) + SET(CMAKE_INSTALL_MANIFEST "install_manifest_${CMAKE_INSTALL_COMPONENT}.txt") +ELSE(CMAKE_INSTALL_COMPONENT) + SET(CMAKE_INSTALL_MANIFEST "install_manifest.txt") +ENDIF(CMAKE_INSTALL_COMPONENT) + +FILE(WRITE "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/${CMAKE_INSTALL_MANIFEST}" "") +FOREACH(file ${CMAKE_INSTALL_MANIFEST_FILES}) + FILE(APPEND "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/${CMAKE_INSTALL_MANIFEST}" "${file}\n") +ENDFOREACH(file) diff --git a/vSLAM/ch9 project/0.3/build/src/CMakeFiles/CMakeDirectoryInformation.cmake b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/CMakeDirectoryInformation.cmake new file mode 100644 index 00000000..6db047a0 --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/CMakeDirectoryInformation.cmake @@ -0,0 +1,16 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Relative path conversion top directories. +SET(CMAKE_RELATIVE_PATH_TOP_SOURCE "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3") +SET(CMAKE_RELATIVE_PATH_TOP_BINARY "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build") + +# Force unix paths in dependencies. +SET(CMAKE_FORCE_UNIX_PATHS 1) + + +# The C and CXX include file regular expressions for this directory. +SET(CMAKE_C_INCLUDE_REGEX_SCAN "^.*$") +SET(CMAKE_C_INCLUDE_REGEX_COMPLAIN "^$") +SET(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN}) +SET(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN}) diff --git a/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/CXX.includecache b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/CXX.includecache new file mode 100644 index 00000000..cd6e2f4a --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/CXX.includecache @@ -0,0 +1,2146 @@ +#IncludeRegexLine: ^[ ]*#[ ]*(include|import)[ ]*[<"]([^">]+)([">]) + +#IncludeRegexScan: ^.*$ + +#IncludeRegexComplain: ^$ + +#IncludeRegexTransform: + +../include/myslam/camera.h +myslam/common_include.h +../include/myslam/myslam/common_include.h + +../include/myslam/common_include.h +Eigen/Core +- +Eigen/Geometry +- +sophus/se3.h +- +sophus/so3.h +- +opencv2/core/core.hpp +- +vector +- +list +- +memory +- +string +- +iostream +- +set +- +unordered_map +- +map +- + +../include/myslam/config.h +myslam/common_include.h +../include/myslam/myslam/common_include.h + +../include/myslam/frame.h +myslam/common_include.h +../include/myslam/myslam/common_include.h +myslam/camera.h +../include/myslam/myslam/camera.h + +../include/myslam/g2o_types.h +myslam/common_include.h +../include/myslam/myslam/common_include.h +camera.h +../include/myslam/camera.h +g2o/core/base_vertex.h +- +g2o/core/base_unary_edge.h +- +g2o/core/block_solver.h +- +g2o/core/optimization_algorithm_levenberg.h +- +g2o/types/sba/types_six_dof_expmap.h +- +g2o/solvers/dense/linear_solver_dense.h +- +g2o/core/robust_kernel.h +- +g2o/core/robust_kernel_impl.h +- + +../include/myslam/map.h +myslam/common_include.h +../include/myslam/myslam/common_include.h +myslam/frame.h +../include/myslam/myslam/frame.h +myslam/mappoint.h +../include/myslam/myslam/mappoint.h + +../include/myslam/mappoint.h + +../include/myslam/visual_odometry.h +myslam/common_include.h +../include/myslam/myslam/common_include.h +myslam/map.h +../include/myslam/myslam/map.h +opencv2/features2d/features2d.hpp +- + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +so3.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +Eigen/Core +- +Eigen/StdVector +- +Eigen/Geometry +- + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/camera.cpp +myslam/camera.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/myslam/camera.h +myslam/config.h +- + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/config.cpp +myslam/config.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/myslam/config.h + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/frame.cpp +myslam/frame.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/myslam/frame.h + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/g2o_types.cpp +myslam/g2o_types.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/myslam/g2o_types.h + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/map.cpp +myslam/map.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/myslam/map.h + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/mappoint.cpp +myslam/common_include.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/myslam/common_include.h +myslam/mappoint.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/myslam/mappoint.h + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/visual_odometry.cpp +opencv2/highgui/highgui.hpp +- +opencv2/imgproc/imgproc.hpp +- +opencv2/calib3d/calib3d.hpp +- +algorithm +- +boost/timer.hpp +- +myslam/config.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/myslam/config.h +myslam/visual_odometry.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/myslam/visual_odometry.h +myslam/g2o_types.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/myslam/g2o_types.h + +/usr/include/eigen3/Eigen/Cholesky +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/Cholesky/LLT.h +/usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/Cholesky/LDLT.h +/usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/Cholesky/LLT_MKL.h +/usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Core/util/Macros.h +/usr/include/eigen3/Eigen/src/Core/util/Macros.h +complex +- +src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +malloc.h +- +immintrin.h +- +emmintrin.h +- +xmmintrin.h +- +pmmintrin.h +- +tmmintrin.h +- +smmintrin.h +- +nmmintrin.h +- +altivec.h +- +arm_neon.h +- +omp.h +- +cerrno +- +cstddef +- +cstdlib +- +cmath +- +cassert +- +functional +- +iosfwd +- +cstring +- +string +- +limits +- +climits +- +algorithm +- +iostream +- +intrin.h +- +new +- +src/Core/util/Constants.h +/usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/Core/util/ForwardDeclarations.h +/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/Core/util/Meta.h +/usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/Core/util/StaticAssert.h +/usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/Core/util/XprHelper.h +/usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/Core/util/Memory.h +/usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/Core/NumTraits.h +/usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/Core/MathFunctions.h +/usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/Core/GenericPacketMath.h +/usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/Core/arch/SSE/PacketMath.h +/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/Core/arch/SSE/MathFunctions.h +/usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/Core/arch/SSE/Complex.h +/usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/Core/arch/AltiVec/PacketMath.h +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/Core/arch/AltiVec/Complex.h +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/Core/arch/NEON/PacketMath.h +/usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/Core/arch/NEON/Complex.h +/usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/Core/arch/Default/Settings.h +/usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/Core/Functors.h +/usr/include/eigen3/Eigen/src/Core/Functors.h +src/Core/DenseCoeffsBase.h +/usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/Core/DenseBase.h +/usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/Core/MatrixBase.h +/usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/Core/EigenBase.h +/usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/Core/Assign.h +/usr/include/eigen3/Eigen/src/Core/Assign.h +src/Core/util/BlasUtil.h +/usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/Core/DenseStorage.h +/usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/Core/NestByValue.h +/usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/Core/ForceAlignedAccess.h +/usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/Core/ReturnByValue.h +/usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/Core/NoAlias.h +/usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/Core/PlainObjectBase.h +/usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/Core/Matrix.h +/usr/include/eigen3/Eigen/src/Core/Matrix.h +src/Core/Array.h +/usr/include/eigen3/Eigen/src/Core/Array.h +src/Core/CwiseBinaryOp.h +/usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/Core/CwiseUnaryOp.h +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/Core/CwiseNullaryOp.h +/usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/Core/CwiseUnaryView.h +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/Core/SelfCwiseBinaryOp.h +/usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/Core/Dot.h +/usr/include/eigen3/Eigen/src/Core/Dot.h +src/Core/StableNorm.h +/usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/Core/MapBase.h +/usr/include/eigen3/Eigen/src/Core/MapBase.h +src/Core/Stride.h +/usr/include/eigen3/Eigen/src/Core/Stride.h +src/Core/Map.h +/usr/include/eigen3/Eigen/src/Core/Map.h +src/Core/Block.h +/usr/include/eigen3/Eigen/src/Core/Block.h +src/Core/VectorBlock.h +/usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/Core/Ref.h +/usr/include/eigen3/Eigen/src/Core/Ref.h +src/Core/Transpose.h +/usr/include/eigen3/Eigen/src/Core/Transpose.h +src/Core/DiagonalMatrix.h +/usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/Core/Diagonal.h +/usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/Core/DiagonalProduct.h +/usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/Core/PermutationMatrix.h +/usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/Core/Transpositions.h +/usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/Core/Redux.h +/usr/include/eigen3/Eigen/src/Core/Redux.h +src/Core/Visitor.h +/usr/include/eigen3/Eigen/src/Core/Visitor.h +src/Core/Fuzzy.h +/usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/Core/IO.h +/usr/include/eigen3/Eigen/src/Core/IO.h +src/Core/Swap.h +/usr/include/eigen3/Eigen/src/Core/Swap.h +src/Core/CommaInitializer.h +/usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/Core/Flagged.h +/usr/include/eigen3/Eigen/src/Core/Flagged.h +src/Core/ProductBase.h +/usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/Core/GeneralProduct.h +/usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/Core/TriangularMatrix.h +/usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/Core/SelfAdjointView.h +/usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/Core/products/GeneralBlockPanelKernel.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/Core/products/Parallelizer.h +/usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/Core/products/CoeffBasedProduct.h +/usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/Core/products/GeneralMatrixVector.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/Core/products/GeneralMatrixMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/Core/SolveTriangular.h +/usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/Core/products/GeneralMatrixMatrixTriangular.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/Core/products/SelfadjointMatrixVector.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/Core/products/SelfadjointMatrixMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/Core/products/SelfadjointProduct.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/Core/products/SelfadjointRank2Update.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/Core/products/TriangularMatrixVector.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/Core/products/TriangularMatrixMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/Core/products/TriangularSolverMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/Core/products/TriangularSolverVector.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/Core/BandMatrix.h +/usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/Core/CoreIterators.h +/usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/Core/BooleanRedux.h +/usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/Core/Select.h +/usr/include/eigen3/Eigen/src/Core/Select.h +src/Core/VectorwiseOp.h +/usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/Core/Random.h +/usr/include/eigen3/Eigen/src/Core/Random.h +src/Core/Replicate.h +/usr/include/eigen3/Eigen/src/Core/Replicate.h +src/Core/Reverse.h +/usr/include/eigen3/Eigen/src/Core/Reverse.h +src/Core/ArrayBase.h +/usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/Core/ArrayWrapper.h +/usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/Core/products/GeneralMatrixMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/Core/products/GeneralMatrixVector_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/Core/products/SelfadjointMatrixMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/Core/products/SelfadjointMatrixVector_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/Core/products/TriangularMatrixMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/Core/products/TriangularMatrixVector_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/Core/products/TriangularSolverMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/Core/Assign_MKL.h +/usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/Core/GlobalFunctions.h +/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +Eigen2Support +/usr/include/eigen3/Eigen/Eigen2Support + +/usr/include/eigen3/Eigen/Dense +Core +/usr/include/eigen3/Eigen/Core +LU +/usr/include/eigen3/Eigen/LU +Cholesky +/usr/include/eigen3/Eigen/Cholesky +QR +/usr/include/eigen3/Eigen/QR +SVD +/usr/include/eigen3/Eigen/SVD +Geometry +/usr/include/eigen3/Eigen/Geometry +Eigenvalues +/usr/include/eigen3/Eigen/Eigenvalues + +/usr/include/eigen3/Eigen/Eigen2Support +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Eigen2Support/Macros.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/Eigen2Support/Memory.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/Eigen2Support/Meta.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/Eigen2Support/Lazy.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/Eigen2Support/Cwise.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/Eigen2Support/CwiseOperators.h +/usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/Eigen2Support/TriangularSolver.h +/usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/Eigen2Support/Block.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/Eigen2Support/VectorBlock.h +/usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/Eigen2Support/Minor.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/Eigen2Support/MathFunctions.h +/usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +iostream +- + +/usr/include/eigen3/Eigen/Eigenvalues +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +Cholesky +/usr/include/eigen3/Eigen/Cholesky +Jacobi +/usr/include/eigen3/Eigen/Jacobi +Householder +/usr/include/eigen3/Eigen/Householder +LU +/usr/include/eigen3/Eigen/LU +Geometry +/usr/include/eigen3/Eigen/Geometry +src/Eigenvalues/Tridiagonalization.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/Eigenvalues/RealSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/Eigenvalues/EigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/Eigenvalues/SelfAdjointEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/Eigenvalues/HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/Eigenvalues/ComplexSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/Eigenvalues/ComplexEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/Eigenvalues/RealQZ.h +/usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/Eigenvalues/GeneralizedEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/Eigenvalues/MatrixBaseEigenvalues.h +/usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/Eigenvalues/RealSchur_MKL.h +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/Eigenvalues/ComplexSchur_MKL.h +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Geometry +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +SVD +/usr/include/eigen3/Eigen/SVD +LU +/usr/include/eigen3/Eigen/LU +limits +- +src/Geometry/OrthoMethods.h +/usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/Geometry/EulerAngles.h +/usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/Geometry/Homogeneous.h +/usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/Geometry/RotationBase.h +/usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/Geometry/Rotation2D.h +/usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/Geometry/Quaternion.h +/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/Geometry/AngleAxis.h +/usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/Geometry/Transform.h +/usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/Geometry/Translation.h +/usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/Geometry/Scaling.h +/usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/Geometry/Hyperplane.h +/usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/Geometry/ParametrizedLine.h +/usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/Geometry/AlignedBox.h +/usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/Geometry/Umeyama.h +/usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/Geometry/arch/Geometry_SSE.h +/usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/Eigen2Support/Geometry/All.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Householder +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Householder/Householder.h +/usr/include/eigen3/Eigen/src/Householder/Householder.h +src/Householder/HouseholderSequence.h +/usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/Householder/BlockHouseholder.h +/usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Jacobi +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Jacobi/Jacobi.h +/usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/LU +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/misc/Kernel.h +/usr/include/eigen3/Eigen/src/misc/Kernel.h +src/misc/Image.h +/usr/include/eigen3/Eigen/src/misc/Image.h +src/LU/FullPivLU.h +/usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/LU/PartialPivLU.h +/usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/LU/PartialPivLU_MKL.h +/usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/LU/Determinant.h +/usr/include/eigen3/Eigen/src/LU/Determinant.h +src/LU/Inverse.h +/usr/include/eigen3/Eigen/src/LU/Inverse.h +src/LU/arch/Inverse_SSE.h +/usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/Eigen2Support/LU.h +/usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/QR +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +Cholesky +/usr/include/eigen3/Eigen/Cholesky +Jacobi +/usr/include/eigen3/Eigen/Jacobi +Householder +/usr/include/eigen3/Eigen/Householder +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/QR/HouseholderQR.h +/usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/QR/FullPivHouseholderQR.h +/usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/QR/ColPivHouseholderQR.h +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/QR/HouseholderQR_MKL.h +/usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/QR/ColPivHouseholderQR_MKL.h +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/Eigen2Support/QR.h +/usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +Eigenvalues +/usr/include/eigen3/Eigen/Eigenvalues + +/usr/include/eigen3/Eigen/SVD +QR +/usr/include/eigen3/Eigen/QR +Householder +/usr/include/eigen3/Eigen/Householder +Jacobi +/usr/include/eigen3/Eigen/Jacobi +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/SVD/JacobiSVD.h +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/SVD/JacobiSVD_MKL.h +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/SVD/UpperBidiagonalization.h +/usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/Eigen2Support/SVD.h +/usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/StdVector +Core +/usr/include/eigen3/Eigen/Core +vector +- +src/StlSupport/StdVector.h +/usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + +/usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + +/usr/include/eigen3/Eigen/src/Cholesky/LLT.h + +/usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Cholesky/Eigen/src/Core/util/MKL_support.h +iostream +- + +/usr/include/eigen3/Eigen/src/Core/Array.h + +/usr/include/eigen3/Eigen/src/Core/ArrayBase.h +../plugins/CommonCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +../plugins/MatrixCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +../plugins/ArrayCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +../plugins/CommonCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +../plugins/MatrixCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +../plugins/ArrayCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + +/usr/include/eigen3/Eigen/src/Core/Assign.h + +/usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + +/usr/include/eigen3/Eigen/src/Core/BandMatrix.h + +/usr/include/eigen3/Eigen/src/Core/Block.h + +/usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + +/usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + +/usr/include/eigen3/Eigen/src/Core/CoreIterators.h + +/usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + +/usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + +/usr/include/eigen3/Eigen/src/Core/DenseBase.h +../plugins/BlockMethods.h +/usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + +/usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + +/usr/include/eigen3/Eigen/src/Core/DenseStorage.h + +/usr/include/eigen3/Eigen/src/Core/Diagonal.h + +/usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + +/usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + +/usr/include/eigen3/Eigen/src/Core/Dot.h + +/usr/include/eigen3/Eigen/src/Core/EigenBase.h + +/usr/include/eigen3/Eigen/src/Core/Flagged.h + +/usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + +/usr/include/eigen3/Eigen/src/Core/Functors.h + +/usr/include/eigen3/Eigen/src/Core/Fuzzy.h + +/usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + +/usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + +/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + +/usr/include/eigen3/Eigen/src/Core/IO.h + +/usr/include/eigen3/Eigen/src/Core/Map.h + +/usr/include/eigen3/Eigen/src/Core/MapBase.h + +/usr/include/eigen3/Eigen/src/Core/MathFunctions.h + +/usr/include/eigen3/Eigen/src/Core/Matrix.h + +/usr/include/eigen3/Eigen/src/Core/MatrixBase.h +../plugins/CommonCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +../plugins/CommonCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +../plugins/MatrixCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +../plugins/MatrixCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/Core/NestByValue.h + +/usr/include/eigen3/Eigen/src/Core/NoAlias.h + +/usr/include/eigen3/Eigen/src/Core/NumTraits.h + +/usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + +/usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + +/usr/include/eigen3/Eigen/src/Core/ProductBase.h + +/usr/include/eigen3/Eigen/src/Core/Random.h + +/usr/include/eigen3/Eigen/src/Core/Redux.h + +/usr/include/eigen3/Eigen/src/Core/Ref.h + +/usr/include/eigen3/Eigen/src/Core/Replicate.h + +/usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + +/usr/include/eigen3/Eigen/src/Core/Reverse.h + +/usr/include/eigen3/Eigen/src/Core/Select.h + +/usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + +/usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + +/usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + +/usr/include/eigen3/Eigen/src/Core/StableNorm.h + +/usr/include/eigen3/Eigen/src/Core/Stride.h + +/usr/include/eigen3/Eigen/src/Core/Swap.h + +/usr/include/eigen3/Eigen/src/Core/Transpose.h + +/usr/include/eigen3/Eigen/src/Core/Transpositions.h + +/usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + +/usr/include/eigen3/Eigen/src/Core/VectorBlock.h + +/usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + +/usr/include/eigen3/Eigen/src/Core/Visitor.h + +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + +/usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + +/usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + +/usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + +/usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + +/usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + +/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + +/usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + +/usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + +/usr/include/eigen3/Eigen/src/Core/util/Constants.h + +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + +/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + +/usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +mkl.h +- +mkl_lapacke.h +- + +/usr/include/eigen3/Eigen/src/Core/util/Macros.h +cstdlib +- +iostream +- + +/usr/include/eigen3/Eigen/src/Core/util/Memory.h +unistd.h +- + +/usr/include/eigen3/Eigen/src/Core/util/Meta.h + +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + +/usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +limits +- +RotationBase.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +Rotation2D.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +Quaternion.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +AngleAxis.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +Transform.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +Translation.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +Scaling.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +AlignedBox.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +Hyperplane.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +ParametrizedLine.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +RotationBase.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +Rotation2D.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +Quaternion.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +AngleAxis.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +Transform.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +Translation.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +Scaling.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +AlignedBox.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +Hyperplane.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +ParametrizedLine.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/././HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/././HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +./ComplexSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +./RealSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +./RealQZ.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +./Tridiagonalization.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +./Tridiagonalization.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + +/usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + +/usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + +/usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + +/usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + +/usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + +/usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + +/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + +/usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + +/usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + +/usr/include/eigen3/Eigen/src/Geometry/Scaling.h + +/usr/include/eigen3/Eigen/src/Geometry/Transform.h + +/usr/include/eigen3/Eigen/src/Geometry/Translation.h + +/usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + +/usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + +/usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + +/usr/include/eigen3/Eigen/src/Householder/Householder.h + +/usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + +/usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + +/usr/include/eigen3/Eigen/src/LU/Determinant.h + +/usr/include/eigen3/Eigen/src/LU/FullPivLU.h + +/usr/include/eigen3/Eigen/src/LU/Inverse.h + +/usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + +/usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/LU/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/QR/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + +/usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + +/usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/QR/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/SVD/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + +/usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +Eigen/src/StlSupport/details.h +/usr/include/eigen3/Eigen/src/StlSupport/Eigen/src/StlSupport/details.h + +/usr/include/eigen3/Eigen/src/StlSupport/details.h + +/usr/include/eigen3/Eigen/src/misc/Image.h + +/usr/include/eigen3/Eigen/src/misc/Kernel.h + +/usr/include/eigen3/Eigen/src/misc/Solve.h + +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + +/usr/local/include/g2o/config.h +g2o/core/eigen_types.h +- + +/usr/local/include/g2o/core/base_binary_edge.h +iostream +- +limits +- +base_edge.h +/usr/local/include/g2o/core/base_edge.h +robust_kernel.h +/usr/local/include/g2o/core/robust_kernel.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +base_binary_edge.hpp +/usr/local/include/g2o/core/base_binary_edge.hpp + +/usr/local/include/g2o/core/base_binary_edge.hpp + +/usr/local/include/g2o/core/base_edge.h +iostream +- +limits +- +Eigen/Core +- +optimizable_graph.h +/usr/local/include/g2o/core/optimizable_graph.h + +/usr/local/include/g2o/core/base_multi_edge.h +iostream +- +iomanip +- +limits +- +Eigen/StdVector +- +base_edge.h +/usr/local/include/g2o/core/base_edge.h +robust_kernel.h +/usr/local/include/g2o/core/robust_kernel.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +base_multi_edge.hpp +/usr/local/include/g2o/core/base_multi_edge.hpp + +/usr/local/include/g2o/core/base_multi_edge.hpp + +/usr/local/include/g2o/core/base_unary_edge.h +iostream +- +cassert +- +limits +- +base_edge.h +/usr/local/include/g2o/core/base_edge.h +robust_kernel.h +/usr/local/include/g2o/core/robust_kernel.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +base_unary_edge.hpp +/usr/local/include/g2o/core/base_unary_edge.hpp + +/usr/local/include/g2o/core/base_unary_edge.hpp + +/usr/local/include/g2o/core/base_vertex.h +optimizable_graph.h +/usr/local/include/g2o/core/optimizable_graph.h +creators.h +/usr/local/include/g2o/core/creators.h +g2o/stuff/macros.h +/usr/local/include/g2o/core/g2o/stuff/macros.h +Eigen/Core +- +Eigen/Dense +- +Eigen/Cholesky +- +Eigen/StdVector +- +stack +- +base_vertex.hpp +/usr/local/include/g2o/core/base_vertex.hpp + +/usr/local/include/g2o/core/base_vertex.hpp + +/usr/local/include/g2o/core/batch_stats.h +iostream +- +vector +- +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/block_solver.h +Eigen/Core +- +solver.h +/usr/local/include/g2o/core/solver.h +linear_solver.h +/usr/local/include/g2o/core/linear_solver.h +sparse_block_matrix.h +/usr/local/include/g2o/core/sparse_block_matrix.h +sparse_block_matrix_diagonal.h +/usr/local/include/g2o/core/sparse_block_matrix_diagonal.h +openmp_mutex.h +/usr/local/include/g2o/core/openmp_mutex.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +block_solver.hpp +/usr/local/include/g2o/core/block_solver.hpp + +/usr/local/include/g2o/core/block_solver.hpp +sparse_optimizer.h +/usr/local/include/g2o/core/sparse_optimizer.h +Eigen/LU +- +fstream +- +iomanip +- +g2o/stuff/timeutil.h +/usr/local/include/g2o/core/g2o/stuff/timeutil.h +g2o/stuff/macros.h +/usr/local/include/g2o/core/g2o/stuff/macros.h +g2o/stuff/misc.h +/usr/local/include/g2o/core/g2o/stuff/misc.h + +/usr/local/include/g2o/core/creators.h +hyper_graph.h +/usr/local/include/g2o/core/hyper_graph.h +string +- +typeinfo +- + +/usr/local/include/g2o/core/eigen_types.h +Eigen/Core +- +Eigen/Geometry +- + +/usr/local/include/g2o/core/g2o_core_api.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h + +/usr/local/include/g2o/core/hyper_graph.h +map +- +set +- +bitset +- +cassert +- +vector +- +limits +- +cstddef +- +unordered_map +- +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/jacobian_workspace.h +Eigen/Core +- +Eigen/StdVector +- +vector +- +cassert +- +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h +hyper_graph.h +/usr/local/include/g2o/core/hyper_graph.h + +/usr/local/include/g2o/core/linear_solver.h +sparse_block_matrix.h +/usr/local/include/g2o/core/sparse_block_matrix.h +sparse_block_matrix_ccs.h +/usr/local/include/g2o/core/sparse_block_matrix_ccs.h + +/usr/local/include/g2o/core/matrix_operations.h +Eigen/Core +- + +/usr/local/include/g2o/core/matrix_structure.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/openmp_mutex.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +omp.h +- +cassert +- + +/usr/local/include/g2o/core/optimizable_graph.h +set +- +iostream +- +list +- +limits +- +cmath +- +typeinfo +- +openmp_mutex.h +/usr/local/include/g2o/core/openmp_mutex.h +hyper_graph.h +/usr/local/include/g2o/core/hyper_graph.h +parameter.h +/usr/local/include/g2o/core/parameter.h +parameter_container.h +/usr/local/include/g2o/core/parameter_container.h +jacobian_workspace.h +/usr/local/include/g2o/core/jacobian_workspace.h +g2o/stuff/macros.h +/usr/local/include/g2o/core/g2o/stuff/macros.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/optimization_algorithm.h +vector +- +utility +- +iosfwd +- +g2o/stuff/property.h +/usr/local/include/g2o/core/g2o/stuff/property.h +hyper_graph.h +/usr/local/include/g2o/core/hyper_graph.h +sparse_block_matrix.h +/usr/local/include/g2o/core/sparse_block_matrix.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/optimization_algorithm_levenberg.h +optimization_algorithm_with_hessian.h +/usr/local/include/g2o/core/optimization_algorithm_with_hessian.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/optimization_algorithm_with_hessian.h +optimization_algorithm.h +/usr/local/include/g2o/core/optimization_algorithm.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/parameter.h +iosfwd +- +hyper_graph.h +/usr/local/include/g2o/core/hyper_graph.h + +/usr/local/include/g2o/core/parameter_container.h +iosfwd +- +map +- +string +- + +/usr/local/include/g2o/core/robust_kernel.h +memory +- +Eigen/Core +- +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/robust_kernel_impl.h +robust_kernel.h +/usr/local/include/g2o/core/robust_kernel.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/solver.h +hyper_graph.h +/usr/local/include/g2o/core/hyper_graph.h +batch_stats.h +/usr/local/include/g2o/core/batch_stats.h +sparse_block_matrix.h +/usr/local/include/g2o/core/sparse_block_matrix.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h +cstddef +- + +/usr/local/include/g2o/core/sparse_block_matrix.h +map +- +vector +- +fstream +- +iostream +- +iomanip +- +cassert +- +Eigen/Core +- +sparse_block_matrix_ccs.h +/usr/local/include/g2o/core/sparse_block_matrix_ccs.h +matrix_structure.h +/usr/local/include/g2o/core/matrix_structure.h +matrix_operations.h +/usr/local/include/g2o/core/matrix_operations.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +sparse_block_matrix.hpp +/usr/local/include/g2o/core/sparse_block_matrix.hpp + +/usr/local/include/g2o/core/sparse_block_matrix.hpp + +/usr/local/include/g2o/core/sparse_block_matrix_ccs.h +vector +- +cassert +- +Eigen/Core +- +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +matrix_operations.h +/usr/local/include/g2o/core/matrix_operations.h +unordered_map +- + +/usr/local/include/g2o/core/sparse_block_matrix_diagonal.h +vector +- +Eigen/Core +- +Eigen/StdVector +- +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +matrix_operations.h +/usr/local/include/g2o/core/matrix_operations.h + +/usr/local/include/g2o/core/sparse_optimizer.h +g2o/stuff/macros.h +/usr/local/include/g2o/core/g2o/stuff/macros.h +optimizable_graph.h +/usr/local/include/g2o/core/optimizable_graph.h +sparse_block_matrix.h +/usr/local/include/g2o/core/sparse_block_matrix.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h +batch_stats.h +/usr/local/include/g2o/core/batch_stats.h +map +- + +/usr/local/include/g2o/solvers/dense/linear_solver_dense.h +g2o/core/linear_solver.h +/usr/local/include/g2o/solvers/dense/g2o/core/linear_solver.h +g2o/core/batch_stats.h +/usr/local/include/g2o/solvers/dense/g2o/core/batch_stats.h +vector +- +utility +- +Eigen/Core +- +Eigen/Cholesky +- + +/usr/local/include/g2o/stuff/g2o_stuff_api.h +g2o/config.h +/usr/local/include/g2o/stuff/g2o/config.h + +/usr/local/include/g2o/stuff/macros.h +float.h +- +math.h +- + +/usr/local/include/g2o/stuff/misc.h +macros.h +/usr/local/include/g2o/stuff/macros.h +cmath +- + +/usr/local/include/g2o/stuff/property.h +string +- +map +- +sstream +- +string_tools.h +/usr/local/include/g2o/stuff/string_tools.h +g2o_stuff_api.h +/usr/local/include/g2o/stuff/g2o_stuff_api.h + +/usr/local/include/g2o/stuff/string_tools.h +string +- +sstream +- +cstdlib +- +vector +- +macros.h +/usr/local/include/g2o/stuff/macros.h +g2o_stuff_api.h +/usr/local/include/g2o/stuff/g2o_stuff_api.h + +/usr/local/include/g2o/stuff/timeutil.h +time.h +- +sys/time.h +- +string +- +g2o_stuff_api.h +/usr/local/include/g2o/stuff/g2o_stuff_api.h + +/usr/local/include/g2o/types/sba/g2o_types_sba_api.h +g2o/config.h +/usr/local/include/g2o/types/sba/g2o/config.h + +/usr/local/include/g2o/types/sba/sbacam.h +Eigen/Core +- +Eigen/Geometry +- +g2o/stuff/misc.h +/usr/local/include/g2o/types/sba/g2o/stuff/misc.h +g2o/stuff/macros.h +/usr/local/include/g2o/types/sba/g2o/stuff/macros.h +g2o/types/slam3d/se3quat.h +/usr/local/include/g2o/types/sba/g2o/types/slam3d/se3quat.h +g2o_types_sba_api.h +/usr/local/include/g2o/types/sba/g2o_types_sba_api.h + +/usr/local/include/g2o/types/sba/types_sba.h +g2o/core/base_vertex.h +/usr/local/include/g2o/types/sba/g2o/core/base_vertex.h +g2o/core/base_binary_edge.h +/usr/local/include/g2o/types/sba/g2o/core/base_binary_edge.h +g2o/core/base_multi_edge.h +/usr/local/include/g2o/types/sba/g2o/core/base_multi_edge.h +sbacam.h +/usr/local/include/g2o/types/sba/sbacam.h +Eigen/Geometry +- +iostream +- +g2o_types_sba_api.h +/usr/local/include/g2o/types/sba/g2o_types_sba_api.h + +/usr/local/include/g2o/types/sba/types_six_dof_expmap.h +g2o/core/base_vertex.h +/usr/local/include/g2o/types/sba/g2o/core/base_vertex.h +g2o/core/base_binary_edge.h +/usr/local/include/g2o/types/sba/g2o/core/base_binary_edge.h +g2o/types/slam3d/se3_ops.h +/usr/local/include/g2o/types/sba/g2o/types/slam3d/se3_ops.h +types_sba.h +/usr/local/include/g2o/types/sba/types_sba.h +Eigen/Geometry +- + +/usr/local/include/g2o/types/slam3d/g2o_types_slam3d_api.h +g2o/config.h +/usr/local/include/g2o/types/slam3d/g2o/config.h + +/usr/local/include/g2o/types/slam3d/se3_ops.h +Eigen/Core +- +Eigen/Geometry +- +g2o_types_slam3d_api.h +/usr/local/include/g2o/types/slam3d/g2o_types_slam3d_api.h +se3_ops.hpp +/usr/local/include/g2o/types/slam3d/se3_ops.hpp + +/usr/local/include/g2o/types/slam3d/se3_ops.hpp + +/usr/local/include/g2o/types/slam3d/se3quat.h +se3_ops.h +/usr/local/include/g2o/types/slam3d/se3_ops.h +Eigen/Core +- +Eigen/Geometry +- + +/usr/local/include/opencv/cxcore.h +opencv2/core/core_c.h +/usr/local/include/opencv/opencv2/core/core_c.h + +/usr/local/include/opencv2/calib3d.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/opencv2/features2d.hpp +opencv2/core/affine.hpp +/usr/local/include/opencv2/opencv2/core/affine.hpp +opencv2/calib3d/calib3d_c.h +/usr/local/include/opencv2/opencv2/calib3d/calib3d_c.h + +/usr/local/include/opencv2/calib3d/calib3d.hpp +opencv2/calib3d.hpp +/usr/local/include/opencv2/calib3d/opencv2/calib3d.hpp + +/usr/local/include/opencv2/calib3d/calib3d_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/calib3d/opencv2/core/core_c.h + +/usr/local/include/opencv2/core.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/opencv2/core/cvdef.h +opencv2/core/version.hpp +/usr/local/include/opencv2/opencv2/core/version.hpp +opencv2/core/base.hpp +/usr/local/include/opencv2/opencv2/core/base.hpp +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/opencv2/core/cvstd.hpp +opencv2/core/traits.hpp +/usr/local/include/opencv2/opencv2/core/traits.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/opencv2/core/matx.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/opencv2/core/types.hpp +opencv2/core/mat.hpp +/usr/local/include/opencv2/opencv2/core/mat.hpp +opencv2/core/persistence.hpp +/usr/local/include/opencv2/opencv2/core/persistence.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/opencv2/opencv.hpp +opencv2/xfeatures2d.hpp +/usr/local/include/opencv2/opencv2/xfeatures2d.hpp +opencv2/core/operations.hpp +/usr/local/include/opencv2/opencv2/core/operations.hpp +opencv2/core/cvstd.inl.hpp +/usr/local/include/opencv2/opencv2/core/cvstd.inl.hpp +opencv2/core/utility.hpp +/usr/local/include/opencv2/opencv2/core/utility.hpp +opencv2/core/optim.hpp +/usr/local/include/opencv2/opencv2/core/optim.hpp + +/usr/local/include/opencv2/core/affine.hpp +opencv2/core.hpp +- + +/usr/local/include/opencv2/core/base.hpp +climits +- +algorithm +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/core/opencv2/core/cvstd.hpp +opencv2/core/neon_utils.hpp +/usr/local/include/opencv2/core/opencv2/core/neon_utils.hpp + +/usr/local/include/opencv2/core/bufferpool.hpp + +/usr/local/include/opencv2/core/core.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/core_c.h +opencv2/core/types_c.h +/usr/local/include/opencv2/core/opencv2/core/types_c.h +cxcore.h +/usr/local/include/opencv2/core/cxcore.h +cxcore.h +/usr/local/include/opencv2/core/cxcore.h +opencv2/core/utility.hpp +/usr/local/include/opencv2/core/opencv2/core/utility.hpp + +/usr/local/include/opencv2/core/cvdef.h +limits.h +- +opencv2/core/hal/interface.h +/usr/local/include/opencv2/core/opencv2/core/hal/interface.h +emmintrin.h +- +pmmintrin.h +- +tmmintrin.h +- +smmintrin.h +- +nmmintrin.h +- +nmmintrin.h +- +popcntintrin.h +- +immintrin.h +- +immintrin.h +- +Intrin.h +- +arm_neon.h +/usr/local/include/opencv2/core/arm_neon.h +arm_neon.h +- +intrin.h +- + +/usr/local/include/opencv2/core/cvstd.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +cstddef +- +cstring +- +cctype +- +string +- +algorithm +- +utility +- +cstdlib +- +cmath +- +opencv2/core/ptr.inl.hpp +/usr/local/include/opencv2/core/opencv2/core/ptr.inl.hpp + +/usr/local/include/opencv2/core/cvstd.inl.hpp +complex +- +ostream +- + +/usr/local/include/opencv2/core/fast_math.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +fastmath.h +- +cmath +- +math.h +- +tegra_round.hpp +/usr/local/include/opencv2/core/tegra_round.hpp + +/usr/local/include/opencv2/core/hal/interface.h +cstddef +- +stddef.h +- +cstdint +- +stdint.h +- + +/usr/local/include/opencv2/core/mat.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/core/opencv2/core/matx.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/core/opencv2/core/types.hpp +opencv2/core/bufferpool.hpp +/usr/local/include/opencv2/core/opencv2/core/bufferpool.hpp +opencv2/core/mat.inl.hpp +/usr/local/include/opencv2/core/opencv2/core/mat.inl.hpp + +/usr/local/include/opencv2/core/mat.inl.hpp + +/usr/local/include/opencv2/core/matx.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/base.hpp +/usr/local/include/opencv2/core/opencv2/core/base.hpp +opencv2/core/traits.hpp +/usr/local/include/opencv2/core/opencv2/core/traits.hpp +opencv2/core/saturate.hpp +/usr/local/include/opencv2/core/opencv2/core/saturate.hpp + +/usr/local/include/opencv2/core/neon_utils.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h + +/usr/local/include/opencv2/core/operations.hpp +cstdio +- + +/usr/local/include/opencv2/core/optim.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/persistence.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/core/opencv2/core/types.hpp +opencv2/core/mat.hpp +/usr/local/include/opencv2/core/opencv2/core/mat.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/core/opencv2/opencv.hpp +time.h +- + +/usr/local/include/opencv2/core/ptr.inl.hpp +algorithm +- + +/usr/local/include/opencv2/core/saturate.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/fast_math.hpp +/usr/local/include/opencv2/core/opencv2/core/fast_math.hpp + +/usr/local/include/opencv2/core/traits.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h + +/usr/local/include/opencv2/core/types.hpp +climits +- +cfloat +- +vector +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/core/opencv2/core/cvstd.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/core/opencv2/core/matx.hpp + +/usr/local/include/opencv2/core/types_c.h +ipl.h +- +ipl/ipl.h +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +assert.h +- +stdlib.h +- +string.h +- +float.h +- +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/utility.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp +opencv2/core/core_c.h +/usr/local/include/opencv2/core/opencv2/core/core_c.h + +/usr/local/include/opencv2/core/version.hpp + +/usr/local/include/opencv2/features2d.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/flann/miniflann.hpp +/usr/local/include/opencv2/opencv2/flann/miniflann.hpp + +/usr/local/include/opencv2/features2d/features2d.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/features2d/opencv2/features2d.hpp + +/usr/local/include/opencv2/flann/config.h + +/usr/local/include/opencv2/flann/defines.h +config.h +/usr/local/include/opencv2/flann/config.h + +/usr/local/include/opencv2/flann/miniflann.hpp +opencv2/core.hpp +/usr/local/include/opencv2/flann/opencv2/core.hpp +opencv2/flann/defines.h +/usr/local/include/opencv2/flann/opencv2/flann/defines.h + +/usr/local/include/opencv2/highgui.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgcodecs.hpp +/usr/local/include/opencv2/opencv2/imgcodecs.hpp +opencv2/videoio.hpp +/usr/local/include/opencv2/opencv2/videoio.hpp +opencv2/highgui/highgui_c.h +/usr/local/include/opencv2/opencv2/highgui/highgui_c.h + +/usr/local/include/opencv2/highgui/highgui.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/highgui/opencv2/highgui.hpp + +/usr/local/include/opencv2/highgui/highgui_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/highgui/opencv2/core/core_c.h +opencv2/imgproc/imgproc_c.h +/usr/local/include/opencv2/highgui/opencv2/imgproc/imgproc_c.h +opencv2/imgcodecs/imgcodecs_c.h +/usr/local/include/opencv2/highgui/opencv2/imgcodecs/imgcodecs_c.h +opencv2/videoio/videoio_c.h +/usr/local/include/opencv2/highgui/opencv2/videoio/videoio_c.h + +/usr/local/include/opencv2/imgcodecs.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/opencv.hpp +- + +/usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/imgcodecs/opencv2/core/core_c.h + +/usr/local/include/opencv2/imgproc.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/core.hpp +- +opencv2/imgproc.hpp +- +opencv2/imgcodecs.hpp +- +opencv2/highgui.hpp +- +iostream +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +math.h +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/opencv2/highgui.hpp +opencv2/imgproc/imgproc_c.h +/usr/local/include/opencv2/opencv2/imgproc/imgproc_c.h + +/usr/local/include/opencv2/imgproc/imgproc.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/imgproc/opencv2/imgproc.hpp + +/usr/local/include/opencv2/imgproc/imgproc_c.h +opencv2/imgproc/types_c.h +/usr/local/include/opencv2/imgproc/opencv2/imgproc/types_c.h + +/usr/local/include/opencv2/imgproc/types_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/imgproc/opencv2/core/core_c.h + +/usr/local/include/opencv2/ml.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +float.h +- +map +- +iostream +- + +/usr/local/include/opencv2/objdetect.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/objdetect/detection_based_tracker.hpp +/usr/local/include/opencv2/opencv2/objdetect/detection_based_tracker.hpp +opencv2/objdetect/objdetect_c.h +/usr/local/include/opencv2/opencv2/objdetect/objdetect_c.h + +/usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +vector +- + +/usr/local/include/opencv2/objdetect/objdetect_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/objdetect/opencv2/core/core_c.h +deque +- +vector +- + +/usr/local/include/opencv2/opencv.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/photo.hpp +/usr/local/include/opencv2/opencv2/photo.hpp +opencv2/video.hpp +/usr/local/include/opencv2/opencv2/video.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/opencv2/features2d.hpp +opencv2/objdetect.hpp +/usr/local/include/opencv2/opencv2/objdetect.hpp +opencv2/calib3d.hpp +/usr/local/include/opencv2/opencv2/calib3d.hpp +opencv2/imgcodecs.hpp +/usr/local/include/opencv2/opencv2/imgcodecs.hpp +opencv2/videoio.hpp +/usr/local/include/opencv2/opencv2/videoio.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/opencv2/highgui.hpp +opencv2/ml.hpp +/usr/local/include/opencv2/opencv2/ml.hpp + +/usr/local/include/opencv2/photo.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/photo/photo_c.h +/usr/local/include/opencv2/opencv2/photo/photo_c.h + +/usr/local/include/opencv2/photo/photo_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/photo/opencv2/core/core_c.h + +/usr/local/include/opencv2/video.hpp +opencv2/video/tracking.hpp +/usr/local/include/opencv2/opencv2/video/tracking.hpp +opencv2/video/background_segm.hpp +/usr/local/include/opencv2/opencv2/video/background_segm.hpp +opencv2/video/tracking_c.h +/usr/local/include/opencv2/opencv2/video/tracking_c.h + +/usr/local/include/opencv2/video/background_segm.hpp +opencv2/core.hpp +/usr/local/include/opencv2/video/opencv2/core.hpp + +/usr/local/include/opencv2/video/tracking.hpp +opencv2/core.hpp +/usr/local/include/opencv2/video/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/video/opencv2/imgproc.hpp + +/usr/local/include/opencv2/video/tracking_c.h +opencv2/imgproc/types_c.h +/usr/local/include/opencv2/video/opencv2/imgproc/types_c.h + +/usr/local/include/opencv2/videoio.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/opencv2/opencv.hpp + +/usr/local/include/opencv2/videoio/videoio_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/videoio/opencv2/core/core_c.h + diff --git a/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/DependInfo.cmake b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/DependInfo.cmake new file mode 100644 index 00000000..b6afcb0b --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/DependInfo.cmake @@ -0,0 +1,31 @@ +# The set of languages for which implicit dependencies are needed: +SET(CMAKE_DEPENDS_LANGUAGES + "CXX" + ) +# The set of files for implicit dependencies of each language: +SET(CMAKE_DEPENDS_CHECK_CXX + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/camera.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/camera.cpp.o" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/config.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/config.cpp.o" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/frame.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/frame.cpp.o" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/g2o_types.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/g2o_types.cpp.o" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/map.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/map.cpp.o" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/mappoint.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/mappoint.cpp.o" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/visual_odometry.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/visual_odometry.cpp.o" + ) +SET(CMAKE_CXX_COMPILER_ID "GNU") + +# Targets to which this target links. +SET(CMAKE_TARGET_LINKED_INFO_FILES + ) + +# The include file search paths: +SET(CMAKE_C_TARGET_INCLUDE_PATH + "/usr/include/eigen3" + "/usr/local/include/opencv" + "/usr/local/include" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus" + "../include" + ) +SET(CMAKE_CXX_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) +SET(CMAKE_Fortran_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) +SET(CMAKE_ASM_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) diff --git a/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/build.make b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/build.make new file mode 100644 index 00000000..fe6a348d --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/build.make @@ -0,0 +1,285 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3" + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" + +# Include any dependencies generated for this target. +include src/CMakeFiles/myslam.dir/depend.make + +# Include the progress variables for this target. +include src/CMakeFiles/myslam.dir/progress.make + +# Include the compile flags for this target's objects. +include src/CMakeFiles/myslam.dir/flags.make + +src/CMakeFiles/myslam.dir/frame.cpp.o: src/CMakeFiles/myslam.dir/flags.make +src/CMakeFiles/myslam.dir/frame.cpp.o: ../src/frame.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles" $(CMAKE_PROGRESS_1) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object src/CMakeFiles/myslam.dir/frame.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/myslam.dir/frame.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/frame.cpp" + +src/CMakeFiles/myslam.dir/frame.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/myslam.dir/frame.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/frame.cpp" > CMakeFiles/myslam.dir/frame.cpp.i + +src/CMakeFiles/myslam.dir/frame.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/myslam.dir/frame.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/frame.cpp" -o CMakeFiles/myslam.dir/frame.cpp.s + +src/CMakeFiles/myslam.dir/frame.cpp.o.requires: +.PHONY : src/CMakeFiles/myslam.dir/frame.cpp.o.requires + +src/CMakeFiles/myslam.dir/frame.cpp.o.provides: src/CMakeFiles/myslam.dir/frame.cpp.o.requires + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/frame.cpp.o.provides.build +.PHONY : src/CMakeFiles/myslam.dir/frame.cpp.o.provides + +src/CMakeFiles/myslam.dir/frame.cpp.o.provides.build: src/CMakeFiles/myslam.dir/frame.cpp.o + +src/CMakeFiles/myslam.dir/mappoint.cpp.o: src/CMakeFiles/myslam.dir/flags.make +src/CMakeFiles/myslam.dir/mappoint.cpp.o: ../src/mappoint.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles" $(CMAKE_PROGRESS_2) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object src/CMakeFiles/myslam.dir/mappoint.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/myslam.dir/mappoint.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/mappoint.cpp" + +src/CMakeFiles/myslam.dir/mappoint.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/myslam.dir/mappoint.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/mappoint.cpp" > CMakeFiles/myslam.dir/mappoint.cpp.i + +src/CMakeFiles/myslam.dir/mappoint.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/myslam.dir/mappoint.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/mappoint.cpp" -o CMakeFiles/myslam.dir/mappoint.cpp.s + +src/CMakeFiles/myslam.dir/mappoint.cpp.o.requires: +.PHONY : src/CMakeFiles/myslam.dir/mappoint.cpp.o.requires + +src/CMakeFiles/myslam.dir/mappoint.cpp.o.provides: src/CMakeFiles/myslam.dir/mappoint.cpp.o.requires + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/mappoint.cpp.o.provides.build +.PHONY : src/CMakeFiles/myslam.dir/mappoint.cpp.o.provides + +src/CMakeFiles/myslam.dir/mappoint.cpp.o.provides.build: src/CMakeFiles/myslam.dir/mappoint.cpp.o + +src/CMakeFiles/myslam.dir/map.cpp.o: src/CMakeFiles/myslam.dir/flags.make +src/CMakeFiles/myslam.dir/map.cpp.o: ../src/map.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles" $(CMAKE_PROGRESS_3) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object src/CMakeFiles/myslam.dir/map.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/myslam.dir/map.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/map.cpp" + +src/CMakeFiles/myslam.dir/map.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/myslam.dir/map.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/map.cpp" > CMakeFiles/myslam.dir/map.cpp.i + +src/CMakeFiles/myslam.dir/map.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/myslam.dir/map.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/map.cpp" -o CMakeFiles/myslam.dir/map.cpp.s + +src/CMakeFiles/myslam.dir/map.cpp.o.requires: +.PHONY : src/CMakeFiles/myslam.dir/map.cpp.o.requires + +src/CMakeFiles/myslam.dir/map.cpp.o.provides: src/CMakeFiles/myslam.dir/map.cpp.o.requires + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/map.cpp.o.provides.build +.PHONY : src/CMakeFiles/myslam.dir/map.cpp.o.provides + +src/CMakeFiles/myslam.dir/map.cpp.o.provides.build: src/CMakeFiles/myslam.dir/map.cpp.o + +src/CMakeFiles/myslam.dir/camera.cpp.o: src/CMakeFiles/myslam.dir/flags.make +src/CMakeFiles/myslam.dir/camera.cpp.o: ../src/camera.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles" $(CMAKE_PROGRESS_4) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object src/CMakeFiles/myslam.dir/camera.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/myslam.dir/camera.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/camera.cpp" + +src/CMakeFiles/myslam.dir/camera.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/myslam.dir/camera.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/camera.cpp" > CMakeFiles/myslam.dir/camera.cpp.i + +src/CMakeFiles/myslam.dir/camera.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/myslam.dir/camera.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/camera.cpp" -o CMakeFiles/myslam.dir/camera.cpp.s + +src/CMakeFiles/myslam.dir/camera.cpp.o.requires: +.PHONY : src/CMakeFiles/myslam.dir/camera.cpp.o.requires + +src/CMakeFiles/myslam.dir/camera.cpp.o.provides: src/CMakeFiles/myslam.dir/camera.cpp.o.requires + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/camera.cpp.o.provides.build +.PHONY : src/CMakeFiles/myslam.dir/camera.cpp.o.provides + +src/CMakeFiles/myslam.dir/camera.cpp.o.provides.build: src/CMakeFiles/myslam.dir/camera.cpp.o + +src/CMakeFiles/myslam.dir/config.cpp.o: src/CMakeFiles/myslam.dir/flags.make +src/CMakeFiles/myslam.dir/config.cpp.o: ../src/config.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles" $(CMAKE_PROGRESS_5) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object src/CMakeFiles/myslam.dir/config.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/myslam.dir/config.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/config.cpp" + +src/CMakeFiles/myslam.dir/config.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/myslam.dir/config.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/config.cpp" > CMakeFiles/myslam.dir/config.cpp.i + +src/CMakeFiles/myslam.dir/config.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/myslam.dir/config.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/config.cpp" -o CMakeFiles/myslam.dir/config.cpp.s + +src/CMakeFiles/myslam.dir/config.cpp.o.requires: +.PHONY : src/CMakeFiles/myslam.dir/config.cpp.o.requires + +src/CMakeFiles/myslam.dir/config.cpp.o.provides: src/CMakeFiles/myslam.dir/config.cpp.o.requires + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/config.cpp.o.provides.build +.PHONY : src/CMakeFiles/myslam.dir/config.cpp.o.provides + +src/CMakeFiles/myslam.dir/config.cpp.o.provides.build: src/CMakeFiles/myslam.dir/config.cpp.o + +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: src/CMakeFiles/myslam.dir/flags.make +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: ../src/g2o_types.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles" $(CMAKE_PROGRESS_6) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object src/CMakeFiles/myslam.dir/g2o_types.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/myslam.dir/g2o_types.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/g2o_types.cpp" + +src/CMakeFiles/myslam.dir/g2o_types.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/myslam.dir/g2o_types.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/g2o_types.cpp" > CMakeFiles/myslam.dir/g2o_types.cpp.i + +src/CMakeFiles/myslam.dir/g2o_types.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/myslam.dir/g2o_types.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/g2o_types.cpp" -o CMakeFiles/myslam.dir/g2o_types.cpp.s + +src/CMakeFiles/myslam.dir/g2o_types.cpp.o.requires: +.PHONY : src/CMakeFiles/myslam.dir/g2o_types.cpp.o.requires + +src/CMakeFiles/myslam.dir/g2o_types.cpp.o.provides: src/CMakeFiles/myslam.dir/g2o_types.cpp.o.requires + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/g2o_types.cpp.o.provides.build +.PHONY : src/CMakeFiles/myslam.dir/g2o_types.cpp.o.provides + +src/CMakeFiles/myslam.dir/g2o_types.cpp.o.provides.build: src/CMakeFiles/myslam.dir/g2o_types.cpp.o + +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: src/CMakeFiles/myslam.dir/flags.make +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../src/visual_odometry.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles" $(CMAKE_PROGRESS_7) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object src/CMakeFiles/myslam.dir/visual_odometry.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/myslam.dir/visual_odometry.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/visual_odometry.cpp" + +src/CMakeFiles/myslam.dir/visual_odometry.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/myslam.dir/visual_odometry.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/visual_odometry.cpp" > CMakeFiles/myslam.dir/visual_odometry.cpp.i + +src/CMakeFiles/myslam.dir/visual_odometry.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/myslam.dir/visual_odometry.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/visual_odometry.cpp" -o CMakeFiles/myslam.dir/visual_odometry.cpp.s + +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o.requires: +.PHONY : src/CMakeFiles/myslam.dir/visual_odometry.cpp.o.requires + +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o.provides: src/CMakeFiles/myslam.dir/visual_odometry.cpp.o.requires + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/visual_odometry.cpp.o.provides.build +.PHONY : src/CMakeFiles/myslam.dir/visual_odometry.cpp.o.provides + +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o.provides.build: src/CMakeFiles/myslam.dir/visual_odometry.cpp.o + +# Object files for target myslam +myslam_OBJECTS = \ +"CMakeFiles/myslam.dir/frame.cpp.o" \ +"CMakeFiles/myslam.dir/mappoint.cpp.o" \ +"CMakeFiles/myslam.dir/map.cpp.o" \ +"CMakeFiles/myslam.dir/camera.cpp.o" \ +"CMakeFiles/myslam.dir/config.cpp.o" \ +"CMakeFiles/myslam.dir/g2o_types.cpp.o" \ +"CMakeFiles/myslam.dir/visual_odometry.cpp.o" + +# External object files for target myslam +myslam_EXTERNAL_OBJECTS = + +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/frame.cpp.o +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/mappoint.cpp.o +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/map.cpp.o +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/camera.cpp.o +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/config.cpp.o +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/g2o_types.cpp.o +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/visual_odometry.cpp.o +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/build.make +../lib/libmyslam.so: /usr/local/lib/libopencv_viz.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_videostab.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_videoio.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_video.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_superres.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_stitching.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_shape.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_photo.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_objdetect.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_ml.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_imgproc.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_imgcodecs.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_highgui.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_flann.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_features2d.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_core.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_calib3d.so.3.1.0 +../lib/libmyslam.so: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build/libSophus.so +../lib/libmyslam.so: /usr/local/lib/libopencv_features2d.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_ml.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_highgui.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_videoio.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_imgcodecs.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_flann.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_video.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_imgproc.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_core.so.3.1.0 +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/link.txt + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --red --bold "Linking CXX shared library ../../lib/libmyslam.so" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src" && $(CMAKE_COMMAND) -E cmake_link_script CMakeFiles/myslam.dir/link.txt --verbose=$(VERBOSE) + +# Rule to build all files generated by this target. +src/CMakeFiles/myslam.dir/build: ../lib/libmyslam.so +.PHONY : src/CMakeFiles/myslam.dir/build + +src/CMakeFiles/myslam.dir/requires: src/CMakeFiles/myslam.dir/frame.cpp.o.requires +src/CMakeFiles/myslam.dir/requires: src/CMakeFiles/myslam.dir/mappoint.cpp.o.requires +src/CMakeFiles/myslam.dir/requires: src/CMakeFiles/myslam.dir/map.cpp.o.requires +src/CMakeFiles/myslam.dir/requires: src/CMakeFiles/myslam.dir/camera.cpp.o.requires +src/CMakeFiles/myslam.dir/requires: src/CMakeFiles/myslam.dir/config.cpp.o.requires +src/CMakeFiles/myslam.dir/requires: src/CMakeFiles/myslam.dir/g2o_types.cpp.o.requires +src/CMakeFiles/myslam.dir/requires: src/CMakeFiles/myslam.dir/visual_odometry.cpp.o.requires +.PHONY : src/CMakeFiles/myslam.dir/requires + +src/CMakeFiles/myslam.dir/clean: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src" && $(CMAKE_COMMAND) -P CMakeFiles/myslam.dir/cmake_clean.cmake +.PHONY : src/CMakeFiles/myslam.dir/clean + +src/CMakeFiles/myslam.dir/depend: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/DependInfo.cmake" --color=$(COLOR) +.PHONY : src/CMakeFiles/myslam.dir/depend + diff --git a/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/camera.cpp.o b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/camera.cpp.o new file mode 100644 index 00000000..844b6ddf Binary files /dev/null and b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/camera.cpp.o differ diff --git a/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/cmake_clean.cmake b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/cmake_clean.cmake new file mode 100644 index 00000000..c3927b8a --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/cmake_clean.cmake @@ -0,0 +1,16 @@ +FILE(REMOVE_RECURSE + "CMakeFiles/myslam.dir/frame.cpp.o" + "CMakeFiles/myslam.dir/mappoint.cpp.o" + "CMakeFiles/myslam.dir/map.cpp.o" + "CMakeFiles/myslam.dir/camera.cpp.o" + "CMakeFiles/myslam.dir/config.cpp.o" + "CMakeFiles/myslam.dir/g2o_types.cpp.o" + "CMakeFiles/myslam.dir/visual_odometry.cpp.o" + "../../lib/libmyslam.pdb" + "../../lib/libmyslam.so" +) + +# Per-language clean rules from dependency scanning. +FOREACH(lang CXX) + INCLUDE(CMakeFiles/myslam.dir/cmake_clean_${lang}.cmake OPTIONAL) +ENDFOREACH(lang) diff --git a/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/config.cpp.o b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/config.cpp.o new file mode 100644 index 00000000..efc49619 Binary files /dev/null and b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/config.cpp.o differ diff --git a/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/depend.internal b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/depend.internal new file mode 100644 index 00000000..f5bf4435 --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/depend.internal @@ -0,0 +1,1957 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +src/CMakeFiles/myslam.dir/camera.cpp.o + ../include/myslam/camera.h + ../include/myslam/common_include.h + ../include/myslam/config.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/camera.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h +src/CMakeFiles/myslam.dir/config.cpp.o + ../include/myslam/common_include.h + ../include/myslam/config.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/config.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o + ../include/myslam/camera.h + ../include/myslam/common_include.h + ../include/myslam/frame.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/frame.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o + ../include/myslam/camera.h + ../include/myslam/common_include.h + ../include/myslam/g2o_types.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/g2o_types.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Dense + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/g2o/config.h + /usr/local/include/g2o/core/base_binary_edge.h + /usr/local/include/g2o/core/base_binary_edge.hpp + /usr/local/include/g2o/core/base_edge.h + /usr/local/include/g2o/core/base_multi_edge.h + /usr/local/include/g2o/core/base_multi_edge.hpp + /usr/local/include/g2o/core/base_unary_edge.h + /usr/local/include/g2o/core/base_unary_edge.hpp + /usr/local/include/g2o/core/base_vertex.h + /usr/local/include/g2o/core/base_vertex.hpp + /usr/local/include/g2o/core/batch_stats.h + /usr/local/include/g2o/core/block_solver.h + /usr/local/include/g2o/core/block_solver.hpp + /usr/local/include/g2o/core/creators.h + /usr/local/include/g2o/core/eigen_types.h + /usr/local/include/g2o/core/g2o_core_api.h + /usr/local/include/g2o/core/hyper_graph.h + /usr/local/include/g2o/core/jacobian_workspace.h + /usr/local/include/g2o/core/linear_solver.h + /usr/local/include/g2o/core/matrix_operations.h + /usr/local/include/g2o/core/matrix_structure.h + /usr/local/include/g2o/core/openmp_mutex.h + /usr/local/include/g2o/core/optimizable_graph.h + /usr/local/include/g2o/core/optimization_algorithm.h + /usr/local/include/g2o/core/optimization_algorithm_levenberg.h + /usr/local/include/g2o/core/optimization_algorithm_with_hessian.h + /usr/local/include/g2o/core/parameter.h + /usr/local/include/g2o/core/parameter_container.h + /usr/local/include/g2o/core/robust_kernel.h + /usr/local/include/g2o/core/robust_kernel_impl.h + /usr/local/include/g2o/core/solver.h + /usr/local/include/g2o/core/sparse_block_matrix.h + /usr/local/include/g2o/core/sparse_block_matrix.hpp + /usr/local/include/g2o/core/sparse_block_matrix_ccs.h + /usr/local/include/g2o/core/sparse_block_matrix_diagonal.h + /usr/local/include/g2o/core/sparse_optimizer.h + /usr/local/include/g2o/solvers/dense/linear_solver_dense.h + /usr/local/include/g2o/stuff/g2o_stuff_api.h + /usr/local/include/g2o/stuff/macros.h + /usr/local/include/g2o/stuff/misc.h + /usr/local/include/g2o/stuff/property.h + /usr/local/include/g2o/stuff/string_tools.h + /usr/local/include/g2o/stuff/timeutil.h + /usr/local/include/g2o/types/sba/g2o_types_sba_api.h + /usr/local/include/g2o/types/sba/sbacam.h + /usr/local/include/g2o/types/sba/types_sba.h + /usr/local/include/g2o/types/sba/types_six_dof_expmap.h + /usr/local/include/g2o/types/slam3d/g2o_types_slam3d_api.h + /usr/local/include/g2o/types/slam3d/se3_ops.h + /usr/local/include/g2o/types/slam3d/se3_ops.hpp + /usr/local/include/g2o/types/slam3d/se3quat.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h +src/CMakeFiles/myslam.dir/map.cpp.o + ../include/myslam/camera.h + ../include/myslam/common_include.h + ../include/myslam/frame.h + ../include/myslam/map.h + ../include/myslam/mappoint.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/map.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o + ../include/myslam/common_include.h + ../include/myslam/mappoint.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/mappoint.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o + ../include/myslam/camera.h + ../include/myslam/common_include.h + ../include/myslam/config.h + ../include/myslam/frame.h + ../include/myslam/g2o_types.h + ../include/myslam/map.h + ../include/myslam/mappoint.h + ../include/myslam/visual_odometry.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src/visual_odometry.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Dense + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/g2o/config.h + /usr/local/include/g2o/core/base_binary_edge.h + /usr/local/include/g2o/core/base_binary_edge.hpp + /usr/local/include/g2o/core/base_edge.h + /usr/local/include/g2o/core/base_multi_edge.h + /usr/local/include/g2o/core/base_multi_edge.hpp + /usr/local/include/g2o/core/base_unary_edge.h + /usr/local/include/g2o/core/base_unary_edge.hpp + /usr/local/include/g2o/core/base_vertex.h + /usr/local/include/g2o/core/base_vertex.hpp + /usr/local/include/g2o/core/batch_stats.h + /usr/local/include/g2o/core/block_solver.h + /usr/local/include/g2o/core/block_solver.hpp + /usr/local/include/g2o/core/creators.h + /usr/local/include/g2o/core/eigen_types.h + /usr/local/include/g2o/core/g2o_core_api.h + /usr/local/include/g2o/core/hyper_graph.h + /usr/local/include/g2o/core/jacobian_workspace.h + /usr/local/include/g2o/core/linear_solver.h + /usr/local/include/g2o/core/matrix_operations.h + /usr/local/include/g2o/core/matrix_structure.h + /usr/local/include/g2o/core/openmp_mutex.h + /usr/local/include/g2o/core/optimizable_graph.h + /usr/local/include/g2o/core/optimization_algorithm.h + /usr/local/include/g2o/core/optimization_algorithm_levenberg.h + /usr/local/include/g2o/core/optimization_algorithm_with_hessian.h + /usr/local/include/g2o/core/parameter.h + /usr/local/include/g2o/core/parameter_container.h + /usr/local/include/g2o/core/robust_kernel.h + /usr/local/include/g2o/core/robust_kernel_impl.h + /usr/local/include/g2o/core/solver.h + /usr/local/include/g2o/core/sparse_block_matrix.h + /usr/local/include/g2o/core/sparse_block_matrix.hpp + /usr/local/include/g2o/core/sparse_block_matrix_ccs.h + /usr/local/include/g2o/core/sparse_block_matrix_diagonal.h + /usr/local/include/g2o/core/sparse_optimizer.h + /usr/local/include/g2o/solvers/dense/linear_solver_dense.h + /usr/local/include/g2o/stuff/g2o_stuff_api.h + /usr/local/include/g2o/stuff/macros.h + /usr/local/include/g2o/stuff/misc.h + /usr/local/include/g2o/stuff/property.h + /usr/local/include/g2o/stuff/string_tools.h + /usr/local/include/g2o/stuff/timeutil.h + /usr/local/include/g2o/types/sba/g2o_types_sba_api.h + /usr/local/include/g2o/types/sba/sbacam.h + /usr/local/include/g2o/types/sba/types_sba.h + /usr/local/include/g2o/types/sba/types_six_dof_expmap.h + /usr/local/include/g2o/types/slam3d/g2o_types_slam3d_api.h + /usr/local/include/g2o/types/slam3d/se3_ops.h + /usr/local/include/g2o/types/slam3d/se3_ops.hpp + /usr/local/include/g2o/types/slam3d/se3quat.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/features2d/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h diff --git a/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/depend.make b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/depend.make new file mode 100644 index 00000000..51ee5172 --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/depend.make @@ -0,0 +1,1957 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +src/CMakeFiles/myslam.dir/camera.cpp.o: ../include/myslam/camera.h +src/CMakeFiles/myslam.dir/camera.cpp.o: ../include/myslam/common_include.h +src/CMakeFiles/myslam.dir/camera.cpp.o: ../include/myslam/config.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +src/CMakeFiles/myslam.dir/camera.cpp.o: ../src/camera.cpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Cholesky +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Core +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Geometry +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Householder +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Jacobi +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/LU +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/QR +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/SVD +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/StdVector +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv/cxcore.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/calib3d.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/affine.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/base.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/core.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/core_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/cvdef.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/mat.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/matx.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/operations.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/optim.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/traits.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/types.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/types_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/utility.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/version.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/features2d.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/flann/config.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/flann/defines.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/highgui.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/imgproc.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/ml.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/objdetect.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/opencv.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/photo.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/video.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/videoio.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + +src/CMakeFiles/myslam.dir/config.cpp.o: ../include/myslam/common_include.h +src/CMakeFiles/myslam.dir/config.cpp.o: ../include/myslam/config.h +src/CMakeFiles/myslam.dir/config.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +src/CMakeFiles/myslam.dir/config.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +src/CMakeFiles/myslam.dir/config.cpp.o: ../src/config.cpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Cholesky +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Core +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Geometry +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Householder +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Jacobi +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/LU +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/QR +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/SVD +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/StdVector +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv/cxcore.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/calib3d.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/affine.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/base.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/core.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/core_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/cvdef.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/mat.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/matx.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/operations.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/optim.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/traits.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/types.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/types_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/utility.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/version.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/features2d.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/flann/config.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/flann/defines.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/highgui.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/imgproc.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/ml.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/objdetect.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/opencv.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/photo.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/video.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/videoio.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + +src/CMakeFiles/myslam.dir/frame.cpp.o: ../include/myslam/camera.h +src/CMakeFiles/myslam.dir/frame.cpp.o: ../include/myslam/common_include.h +src/CMakeFiles/myslam.dir/frame.cpp.o: ../include/myslam/frame.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +src/CMakeFiles/myslam.dir/frame.cpp.o: ../src/frame.cpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Cholesky +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Core +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Geometry +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Householder +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Jacobi +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/LU +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/QR +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/SVD +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/StdVector +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv/cxcore.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/calib3d.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/affine.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/base.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/core.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/core_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/cvdef.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/mat.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/matx.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/operations.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/optim.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/traits.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/types.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/types_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/utility.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/version.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/features2d.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/flann/config.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/flann/defines.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/highgui.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/imgproc.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/ml.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/objdetect.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/opencv.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/photo.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/video.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/videoio.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: ../include/myslam/camera.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: ../include/myslam/common_include.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: ../include/myslam/g2o_types.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: ../src/g2o_types.cpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/Cholesky +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/Core +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/Dense +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/Geometry +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/Householder +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/Jacobi +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/LU +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/QR +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/SVD +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/StdVector +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/config.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/base_binary_edge.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/base_binary_edge.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/base_edge.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/base_multi_edge.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/base_multi_edge.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/base_unary_edge.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/base_unary_edge.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/base_vertex.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/base_vertex.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/batch_stats.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/block_solver.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/block_solver.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/creators.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/eigen_types.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/g2o_core_api.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/hyper_graph.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/jacobian_workspace.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/linear_solver.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/matrix_operations.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/matrix_structure.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/openmp_mutex.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/optimizable_graph.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/optimization_algorithm.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/optimization_algorithm_levenberg.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/optimization_algorithm_with_hessian.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/parameter.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/parameter_container.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/robust_kernel.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/robust_kernel_impl.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/solver.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/sparse_block_matrix.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/sparse_block_matrix.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/sparse_block_matrix_ccs.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/sparse_block_matrix_diagonal.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/sparse_optimizer.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/solvers/dense/linear_solver_dense.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/stuff/g2o_stuff_api.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/stuff/macros.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/stuff/misc.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/stuff/property.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/stuff/string_tools.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/stuff/timeutil.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/types/sba/g2o_types_sba_api.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/types/sba/sbacam.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/types/sba/types_sba.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/types/sba/types_six_dof_expmap.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/types/slam3d/g2o_types_slam3d_api.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/types/slam3d/se3_ops.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/types/slam3d/se3_ops.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/types/slam3d/se3quat.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv/cxcore.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/calib3d.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/affine.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/base.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/core.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/core_c.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/cvdef.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/mat.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/matx.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/operations.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/optim.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/traits.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/types.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/types_c.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/utility.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/version.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/features2d.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/flann/config.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/flann/defines.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/highgui.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/imgproc.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/ml.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/objdetect.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/opencv.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/photo.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/video.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/videoio.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + +src/CMakeFiles/myslam.dir/map.cpp.o: ../include/myslam/camera.h +src/CMakeFiles/myslam.dir/map.cpp.o: ../include/myslam/common_include.h +src/CMakeFiles/myslam.dir/map.cpp.o: ../include/myslam/frame.h +src/CMakeFiles/myslam.dir/map.cpp.o: ../include/myslam/map.h +src/CMakeFiles/myslam.dir/map.cpp.o: ../include/myslam/mappoint.h +src/CMakeFiles/myslam.dir/map.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +src/CMakeFiles/myslam.dir/map.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +src/CMakeFiles/myslam.dir/map.cpp.o: ../src/map.cpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Cholesky +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Core +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Geometry +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Householder +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Jacobi +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/LU +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/QR +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/SVD +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/StdVector +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv/cxcore.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/calib3d.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/affine.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/base.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/core.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/core_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/cvdef.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/mat.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/matx.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/operations.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/optim.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/traits.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/types.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/types_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/utility.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/version.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/features2d.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/flann/config.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/flann/defines.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/highgui.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/imgproc.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/ml.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/objdetect.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/opencv.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/photo.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/video.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/videoio.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + +src/CMakeFiles/myslam.dir/mappoint.cpp.o: ../include/myslam/common_include.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: ../include/myslam/mappoint.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: ../src/mappoint.cpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Cholesky +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Core +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Geometry +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Householder +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Jacobi +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/LU +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/QR +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/SVD +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/StdVector +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv/cxcore.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/calib3d.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/affine.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/base.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/core.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/core_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/cvdef.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/mat.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/matx.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/operations.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/optim.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/traits.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/types.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/types_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/utility.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/version.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/features2d.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/flann/config.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/flann/defines.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/highgui.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/imgproc.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/ml.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/objdetect.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/opencv.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/photo.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/video.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/videoio.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../include/myslam/camera.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../include/myslam/common_include.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../include/myslam/config.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../include/myslam/frame.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../include/myslam/g2o_types.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../include/myslam/map.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../include/myslam/mappoint.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../include/myslam/visual_odometry.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../src/visual_odometry.cpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/Cholesky +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/Core +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/Dense +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/Geometry +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/Householder +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/Jacobi +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/LU +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/QR +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/SVD +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/StdVector +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/config.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/base_binary_edge.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/base_binary_edge.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/base_edge.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/base_multi_edge.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/base_multi_edge.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/base_unary_edge.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/base_unary_edge.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/base_vertex.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/base_vertex.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/batch_stats.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/block_solver.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/block_solver.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/creators.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/eigen_types.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/g2o_core_api.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/hyper_graph.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/jacobian_workspace.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/linear_solver.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/matrix_operations.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/matrix_structure.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/openmp_mutex.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/optimizable_graph.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/optimization_algorithm.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/optimization_algorithm_levenberg.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/optimization_algorithm_with_hessian.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/parameter.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/parameter_container.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/robust_kernel.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/robust_kernel_impl.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/solver.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/sparse_block_matrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/sparse_block_matrix.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/sparse_block_matrix_ccs.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/sparse_block_matrix_diagonal.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/sparse_optimizer.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/solvers/dense/linear_solver_dense.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/stuff/g2o_stuff_api.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/stuff/macros.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/stuff/misc.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/stuff/property.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/stuff/string_tools.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/stuff/timeutil.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/types/sba/g2o_types_sba_api.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/types/sba/sbacam.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/types/sba/types_sba.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/types/sba/types_six_dof_expmap.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/types/slam3d/g2o_types_slam3d_api.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/types/slam3d/se3_ops.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/types/slam3d/se3_ops.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/types/slam3d/se3quat.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv/cxcore.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/calib3d.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/calib3d/calib3d.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/affine.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/base.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/core.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/core_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/cvdef.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/mat.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/matx.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/operations.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/optim.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/traits.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/types.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/types_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/utility.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/version.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/features2d.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/features2d/features2d.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/flann/config.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/flann/defines.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/highgui.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/highgui/highgui.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/imgproc.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/imgproc/imgproc.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/ml.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/objdetect.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/opencv.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/photo.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/video.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/videoio.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + diff --git a/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/flags.make b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/flags.make new file mode 100644 index 00000000..43b4df5c --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/flags.make @@ -0,0 +1,8 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# compile CXX with g++ +CXX_FLAGS = -std=c++11 -march=native -O3 -O3 -DNDEBUG -fPIC -I/usr/include/eigen3 -I/usr/local/include/opencv -I/usr/local/include -I/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus -I"/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/include" + +CXX_DEFINES = -Dmyslam_EXPORTS + diff --git a/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/frame.cpp.o b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/frame.cpp.o new file mode 100644 index 00000000..63e3fecb Binary files /dev/null and b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/frame.cpp.o differ diff --git a/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/g2o_types.cpp.o b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/g2o_types.cpp.o new file mode 100644 index 00000000..e9724d79 Binary files /dev/null and b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/g2o_types.cpp.o differ diff --git a/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/link.txt b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/link.txt new file mode 100644 index 00000000..e297419d --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/link.txt @@ -0,0 +1 @@ +g++ -fPIC -std=c++11 -march=native -O3 -O3 -DNDEBUG -shared -Wl,-soname,libmyslam.so -o ../../lib/libmyslam.so CMakeFiles/myslam.dir/frame.cpp.o CMakeFiles/myslam.dir/mappoint.cpp.o CMakeFiles/myslam.dir/map.cpp.o CMakeFiles/myslam.dir/camera.cpp.o CMakeFiles/myslam.dir/config.cpp.o CMakeFiles/myslam.dir/g2o_types.cpp.o CMakeFiles/myslam.dir/visual_odometry.cpp.o /usr/local/lib/libopencv_viz.so.3.1.0 /usr/local/lib/libopencv_videostab.so.3.1.0 /usr/local/lib/libopencv_videoio.so.3.1.0 /usr/local/lib/libopencv_video.so.3.1.0 /usr/local/lib/libopencv_superres.so.3.1.0 /usr/local/lib/libopencv_stitching.so.3.1.0 /usr/local/lib/libopencv_shape.so.3.1.0 /usr/local/lib/libopencv_photo.so.3.1.0 /usr/local/lib/libopencv_objdetect.so.3.1.0 /usr/local/lib/libopencv_ml.so.3.1.0 /usr/local/lib/libopencv_imgproc.so.3.1.0 /usr/local/lib/libopencv_imgcodecs.so.3.1.0 /usr/local/lib/libopencv_highgui.so.3.1.0 /usr/local/lib/libopencv_flann.so.3.1.0 /usr/local/lib/libopencv_features2d.so.3.1.0 /usr/local/lib/libopencv_core.so.3.1.0 /usr/local/lib/libopencv_calib3d.so.3.1.0 /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build/libSophus.so -lg2o_core -lg2o_stuff -lg2o_types_sba /usr/local/lib/libopencv_features2d.so.3.1.0 /usr/local/lib/libopencv_ml.so.3.1.0 /usr/local/lib/libopencv_highgui.so.3.1.0 /usr/local/lib/libopencv_videoio.so.3.1.0 /usr/local/lib/libopencv_imgcodecs.so.3.1.0 /usr/local/lib/libopencv_flann.so.3.1.0 /usr/local/lib/libopencv_video.so.3.1.0 /usr/local/lib/libopencv_imgproc.so.3.1.0 /usr/local/lib/libopencv_core.so.3.1.0 -Wl,-rpath,/usr/local/lib:/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build diff --git a/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/map.cpp.o b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/map.cpp.o new file mode 100644 index 00000000..c19116e7 Binary files /dev/null and b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/map.cpp.o differ diff --git a/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/mappoint.cpp.o b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/mappoint.cpp.o new file mode 100644 index 00000000..f57cba25 Binary files /dev/null and b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/mappoint.cpp.o differ diff --git a/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/progress.make b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/progress.make new file mode 100644 index 00000000..2f823159 --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/progress.make @@ -0,0 +1,8 @@ +CMAKE_PROGRESS_1 = 1 +CMAKE_PROGRESS_2 = 2 +CMAKE_PROGRESS_3 = 3 +CMAKE_PROGRESS_4 = 4 +CMAKE_PROGRESS_5 = 5 +CMAKE_PROGRESS_6 = 6 +CMAKE_PROGRESS_7 = 7 + diff --git a/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/visual_odometry.cpp.o b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/visual_odometry.cpp.o new file mode 100644 index 00000000..8ceca38a Binary files /dev/null and b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/visual_odometry.cpp.o differ diff --git a/vSLAM/ch9 project/0.3/build/src/CMakeFiles/progress.marks b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/progress.marks new file mode 100644 index 00000000..7f8f011e --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/src/CMakeFiles/progress.marks @@ -0,0 +1 @@ +7 diff --git a/vSLAM/ch9 project/0.3/build/src/Makefile b/vSLAM/ch9 project/0.3/build/src/Makefile new file mode 100644 index 00000000..843879f2 --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/src/Makefile @@ -0,0 +1,326 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Default target executed when no arguments are given to make. +default_target: all +.PHONY : default_target + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3" + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" + +#============================================================================= +# Targets provided globally by CMake. + +# Special rule for the target edit_cache +edit_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running interactive CMake command-line interface..." + /usr/bin/cmake -i . +.PHONY : edit_cache + +# Special rule for the target edit_cache +edit_cache/fast: edit_cache +.PHONY : edit_cache/fast + +# Special rule for the target rebuild_cache +rebuild_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake to regenerate build system..." + /usr/bin/cmake -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) +.PHONY : rebuild_cache + +# Special rule for the target rebuild_cache +rebuild_cache/fast: rebuild_cache +.PHONY : rebuild_cache/fast + +# The main all target +all: cmake_check_build_system + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src/CMakeFiles/progress.marks" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f CMakeFiles/Makefile2 src/all + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles" 0 +.PHONY : all + +# The main clean target +clean: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f CMakeFiles/Makefile2 src/clean +.PHONY : clean + +# The main clean target +clean/fast: clean +.PHONY : clean/fast + +# Prepare targets for installation. +preinstall: all + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f CMakeFiles/Makefile2 src/preinstall +.PHONY : preinstall + +# Prepare targets for installation. +preinstall/fast: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f CMakeFiles/Makefile2 src/preinstall +.PHONY : preinstall/fast + +# clear depends +depend: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 1 +.PHONY : depend + +# Convenience name for target. +src/CMakeFiles/myslam.dir/rule: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f CMakeFiles/Makefile2 src/CMakeFiles/myslam.dir/rule +.PHONY : src/CMakeFiles/myslam.dir/rule + +# Convenience name for target. +myslam: src/CMakeFiles/myslam.dir/rule +.PHONY : myslam + +# fast build rule for target. +myslam/fast: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/build +.PHONY : myslam/fast + +camera.o: camera.cpp.o +.PHONY : camera.o + +# target to build an object file +camera.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/camera.cpp.o +.PHONY : camera.cpp.o + +camera.i: camera.cpp.i +.PHONY : camera.i + +# target to preprocess a source file +camera.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/camera.cpp.i +.PHONY : camera.cpp.i + +camera.s: camera.cpp.s +.PHONY : camera.s + +# target to generate assembly for a file +camera.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/camera.cpp.s +.PHONY : camera.cpp.s + +config.o: config.cpp.o +.PHONY : config.o + +# target to build an object file +config.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/config.cpp.o +.PHONY : config.cpp.o + +config.i: config.cpp.i +.PHONY : config.i + +# target to preprocess a source file +config.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/config.cpp.i +.PHONY : config.cpp.i + +config.s: config.cpp.s +.PHONY : config.s + +# target to generate assembly for a file +config.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/config.cpp.s +.PHONY : config.cpp.s + +frame.o: frame.cpp.o +.PHONY : frame.o + +# target to build an object file +frame.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/frame.cpp.o +.PHONY : frame.cpp.o + +frame.i: frame.cpp.i +.PHONY : frame.i + +# target to preprocess a source file +frame.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/frame.cpp.i +.PHONY : frame.cpp.i + +frame.s: frame.cpp.s +.PHONY : frame.s + +# target to generate assembly for a file +frame.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/frame.cpp.s +.PHONY : frame.cpp.s + +g2o_types.o: g2o_types.cpp.o +.PHONY : g2o_types.o + +# target to build an object file +g2o_types.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/g2o_types.cpp.o +.PHONY : g2o_types.cpp.o + +g2o_types.i: g2o_types.cpp.i +.PHONY : g2o_types.i + +# target to preprocess a source file +g2o_types.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/g2o_types.cpp.i +.PHONY : g2o_types.cpp.i + +g2o_types.s: g2o_types.cpp.s +.PHONY : g2o_types.s + +# target to generate assembly for a file +g2o_types.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/g2o_types.cpp.s +.PHONY : g2o_types.cpp.s + +map.o: map.cpp.o +.PHONY : map.o + +# target to build an object file +map.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/map.cpp.o +.PHONY : map.cpp.o + +map.i: map.cpp.i +.PHONY : map.i + +# target to preprocess a source file +map.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/map.cpp.i +.PHONY : map.cpp.i + +map.s: map.cpp.s +.PHONY : map.s + +# target to generate assembly for a file +map.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/map.cpp.s +.PHONY : map.cpp.s + +mappoint.o: mappoint.cpp.o +.PHONY : mappoint.o + +# target to build an object file +mappoint.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/mappoint.cpp.o +.PHONY : mappoint.cpp.o + +mappoint.i: mappoint.cpp.i +.PHONY : mappoint.i + +# target to preprocess a source file +mappoint.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/mappoint.cpp.i +.PHONY : mappoint.cpp.i + +mappoint.s: mappoint.cpp.s +.PHONY : mappoint.s + +# target to generate assembly for a file +mappoint.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/mappoint.cpp.s +.PHONY : mappoint.cpp.s + +visual_odometry.o: visual_odometry.cpp.o +.PHONY : visual_odometry.o + +# target to build an object file +visual_odometry.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/visual_odometry.cpp.o +.PHONY : visual_odometry.cpp.o + +visual_odometry.i: visual_odometry.cpp.i +.PHONY : visual_odometry.i + +# target to preprocess a source file +visual_odometry.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/visual_odometry.cpp.i +.PHONY : visual_odometry.cpp.i + +visual_odometry.s: visual_odometry.cpp.s +.PHONY : visual_odometry.s + +# target to generate assembly for a file +visual_odometry.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/visual_odometry.cpp.s +.PHONY : visual_odometry.cpp.s + +# Help Target +help: + @echo "The following are some of the valid targets for this Makefile:" + @echo "... all (the default if no target is provided)" + @echo "... clean" + @echo "... depend" + @echo "... edit_cache" + @echo "... myslam" + @echo "... rebuild_cache" + @echo "... camera.o" + @echo "... camera.i" + @echo "... camera.s" + @echo "... config.o" + @echo "... config.i" + @echo "... config.s" + @echo "... frame.o" + @echo "... frame.i" + @echo "... frame.s" + @echo "... g2o_types.o" + @echo "... g2o_types.i" + @echo "... g2o_types.s" + @echo "... map.o" + @echo "... map.i" + @echo "... map.s" + @echo "... mappoint.o" + @echo "... mappoint.i" + @echo "... mappoint.s" + @echo "... visual_odometry.o" + @echo "... visual_odometry.i" + @echo "... visual_odometry.s" +.PHONY : help + + + +#============================================================================= +# Special targets to cleanup operation of make. + +# Special rule to run CMake to check the build system integrity. +# No rule that depends on this can have commands that come from listfiles +# because they might be regenerated. +cmake_check_build_system: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0 +.PHONY : cmake_check_build_system + diff --git a/vSLAM/ch9 project/0.3/build/src/cmake_install.cmake b/vSLAM/ch9 project/0.3/build/src/cmake_install.cmake new file mode 100644 index 00000000..0a1927a1 --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/src/cmake_install.cmake @@ -0,0 +1,34 @@ +# Install script for directory: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/src + +# Set the install prefix +IF(NOT DEFINED CMAKE_INSTALL_PREFIX) + SET(CMAKE_INSTALL_PREFIX "/usr/local") +ENDIF(NOT DEFINED CMAKE_INSTALL_PREFIX) +STRING(REGEX REPLACE "/$" "" CMAKE_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}") + +# Set the install configuration name. +IF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + IF(BUILD_TYPE) + STRING(REGEX REPLACE "^[^A-Za-z0-9_]+" "" + CMAKE_INSTALL_CONFIG_NAME "${BUILD_TYPE}") + ELSE(BUILD_TYPE) + SET(CMAKE_INSTALL_CONFIG_NAME "Release") + ENDIF(BUILD_TYPE) + MESSAGE(STATUS "Install configuration: \"${CMAKE_INSTALL_CONFIG_NAME}\"") +ENDIF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + +# Set the component getting installed. +IF(NOT CMAKE_INSTALL_COMPONENT) + IF(COMPONENT) + MESSAGE(STATUS "Install component: \"${COMPONENT}\"") + SET(CMAKE_INSTALL_COMPONENT "${COMPONENT}") + ELSE(COMPONENT) + SET(CMAKE_INSTALL_COMPONENT) + ENDIF(COMPONENT) +ENDIF(NOT CMAKE_INSTALL_COMPONENT) + +# Install shared libraries without execute permission? +IF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + SET(CMAKE_INSTALL_SO_NO_EXE "1") +ENDIF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + diff --git a/vSLAM/ch9 project/0.3/build/test/CMakeFiles/CMakeDirectoryInformation.cmake b/vSLAM/ch9 project/0.3/build/test/CMakeFiles/CMakeDirectoryInformation.cmake new file mode 100644 index 00000000..6db047a0 --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/test/CMakeFiles/CMakeDirectoryInformation.cmake @@ -0,0 +1,16 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Relative path conversion top directories. +SET(CMAKE_RELATIVE_PATH_TOP_SOURCE "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3") +SET(CMAKE_RELATIVE_PATH_TOP_BINARY "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build") + +# Force unix paths in dependencies. +SET(CMAKE_FORCE_UNIX_PATHS 1) + + +# The C and CXX include file regular expressions for this directory. +SET(CMAKE_C_INCLUDE_REGEX_SCAN "^.*$") +SET(CMAKE_C_INCLUDE_REGEX_COMPLAIN "^$") +SET(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN}) +SET(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN}) diff --git a/vSLAM/ch9 project/0.3/build/test/CMakeFiles/progress.marks b/vSLAM/ch9 project/0.3/build/test/CMakeFiles/progress.marks new file mode 100644 index 00000000..45a4fb75 --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/test/CMakeFiles/progress.marks @@ -0,0 +1 @@ +8 diff --git a/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/CXX.includecache b/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/CXX.includecache new file mode 100644 index 00000000..ccee0c1d --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/CXX.includecache @@ -0,0 +1,1600 @@ +#IncludeRegexLine: ^[ ]*#[ ]*(include|import)[ ]*[<"]([^">]+)([">]) + +#IncludeRegexScan: ^.*$ + +#IncludeRegexComplain: ^$ + +#IncludeRegexTransform: + +../include/myslam/camera.h +myslam/common_include.h +../include/myslam/myslam/common_include.h + +../include/myslam/common_include.h +Eigen/Core +- +Eigen/Geometry +- +sophus/se3.h +- +sophus/so3.h +- +opencv2/core/core.hpp +- +vector +- +list +- +memory +- +string +- +iostream +- +set +- +unordered_map +- +map +- + +../include/myslam/config.h +myslam/common_include.h +../include/myslam/myslam/common_include.h + +../include/myslam/frame.h +myslam/common_include.h +../include/myslam/myslam/common_include.h +myslam/camera.h +../include/myslam/myslam/camera.h + +../include/myslam/map.h +myslam/common_include.h +../include/myslam/myslam/common_include.h +myslam/frame.h +../include/myslam/myslam/frame.h +myslam/mappoint.h +../include/myslam/myslam/mappoint.h + +../include/myslam/mappoint.h + +../include/myslam/visual_odometry.h +myslam/common_include.h +../include/myslam/myslam/common_include.h +myslam/map.h +../include/myslam/myslam/map.h +opencv2/features2d/features2d.hpp +- + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +so3.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +Eigen/Core +- +Eigen/StdVector +- +Eigen/Geometry +- + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/test/run_vo.cpp +fstream +- +boost/timer.hpp +- +opencv2/imgcodecs.hpp +- +opencv2/highgui/highgui.hpp +- +opencv2/viz.hpp +- +myslam/config.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/test/myslam/config.h +myslam/visual_odometry.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/test/myslam/visual_odometry.h + +/usr/include/eigen3/Eigen/Cholesky +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/Cholesky/LLT.h +/usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/Cholesky/LDLT.h +/usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/Cholesky/LLT_MKL.h +/usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Core/util/Macros.h +/usr/include/eigen3/Eigen/src/Core/util/Macros.h +complex +- +src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +malloc.h +- +immintrin.h +- +emmintrin.h +- +xmmintrin.h +- +pmmintrin.h +- +tmmintrin.h +- +smmintrin.h +- +nmmintrin.h +- +altivec.h +- +arm_neon.h +- +omp.h +- +cerrno +- +cstddef +- +cstdlib +- +cmath +- +cassert +- +functional +- +iosfwd +- +cstring +- +string +- +limits +- +climits +- +algorithm +- +iostream +- +intrin.h +- +new +- +src/Core/util/Constants.h +/usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/Core/util/ForwardDeclarations.h +/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/Core/util/Meta.h +/usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/Core/util/StaticAssert.h +/usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/Core/util/XprHelper.h +/usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/Core/util/Memory.h +/usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/Core/NumTraits.h +/usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/Core/MathFunctions.h +/usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/Core/GenericPacketMath.h +/usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/Core/arch/SSE/PacketMath.h +/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/Core/arch/SSE/MathFunctions.h +/usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/Core/arch/SSE/Complex.h +/usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/Core/arch/AltiVec/PacketMath.h +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/Core/arch/AltiVec/Complex.h +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/Core/arch/NEON/PacketMath.h +/usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/Core/arch/NEON/Complex.h +/usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/Core/arch/Default/Settings.h +/usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/Core/Functors.h +/usr/include/eigen3/Eigen/src/Core/Functors.h +src/Core/DenseCoeffsBase.h +/usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/Core/DenseBase.h +/usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/Core/MatrixBase.h +/usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/Core/EigenBase.h +/usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/Core/Assign.h +/usr/include/eigen3/Eigen/src/Core/Assign.h +src/Core/util/BlasUtil.h +/usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/Core/DenseStorage.h +/usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/Core/NestByValue.h +/usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/Core/ForceAlignedAccess.h +/usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/Core/ReturnByValue.h +/usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/Core/NoAlias.h +/usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/Core/PlainObjectBase.h +/usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/Core/Matrix.h +/usr/include/eigen3/Eigen/src/Core/Matrix.h +src/Core/Array.h +/usr/include/eigen3/Eigen/src/Core/Array.h +src/Core/CwiseBinaryOp.h +/usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/Core/CwiseUnaryOp.h +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/Core/CwiseNullaryOp.h +/usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/Core/CwiseUnaryView.h +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/Core/SelfCwiseBinaryOp.h +/usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/Core/Dot.h +/usr/include/eigen3/Eigen/src/Core/Dot.h +src/Core/StableNorm.h +/usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/Core/MapBase.h +/usr/include/eigen3/Eigen/src/Core/MapBase.h +src/Core/Stride.h +/usr/include/eigen3/Eigen/src/Core/Stride.h +src/Core/Map.h +/usr/include/eigen3/Eigen/src/Core/Map.h +src/Core/Block.h +/usr/include/eigen3/Eigen/src/Core/Block.h +src/Core/VectorBlock.h +/usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/Core/Ref.h +/usr/include/eigen3/Eigen/src/Core/Ref.h +src/Core/Transpose.h +/usr/include/eigen3/Eigen/src/Core/Transpose.h +src/Core/DiagonalMatrix.h +/usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/Core/Diagonal.h +/usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/Core/DiagonalProduct.h +/usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/Core/PermutationMatrix.h +/usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/Core/Transpositions.h +/usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/Core/Redux.h +/usr/include/eigen3/Eigen/src/Core/Redux.h +src/Core/Visitor.h +/usr/include/eigen3/Eigen/src/Core/Visitor.h +src/Core/Fuzzy.h +/usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/Core/IO.h +/usr/include/eigen3/Eigen/src/Core/IO.h +src/Core/Swap.h +/usr/include/eigen3/Eigen/src/Core/Swap.h +src/Core/CommaInitializer.h +/usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/Core/Flagged.h +/usr/include/eigen3/Eigen/src/Core/Flagged.h +src/Core/ProductBase.h +/usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/Core/GeneralProduct.h +/usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/Core/TriangularMatrix.h +/usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/Core/SelfAdjointView.h +/usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/Core/products/GeneralBlockPanelKernel.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/Core/products/Parallelizer.h +/usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/Core/products/CoeffBasedProduct.h +/usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/Core/products/GeneralMatrixVector.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/Core/products/GeneralMatrixMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/Core/SolveTriangular.h +/usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/Core/products/GeneralMatrixMatrixTriangular.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/Core/products/SelfadjointMatrixVector.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/Core/products/SelfadjointMatrixMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/Core/products/SelfadjointProduct.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/Core/products/SelfadjointRank2Update.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/Core/products/TriangularMatrixVector.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/Core/products/TriangularMatrixMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/Core/products/TriangularSolverMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/Core/products/TriangularSolverVector.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/Core/BandMatrix.h +/usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/Core/CoreIterators.h +/usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/Core/BooleanRedux.h +/usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/Core/Select.h +/usr/include/eigen3/Eigen/src/Core/Select.h +src/Core/VectorwiseOp.h +/usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/Core/Random.h +/usr/include/eigen3/Eigen/src/Core/Random.h +src/Core/Replicate.h +/usr/include/eigen3/Eigen/src/Core/Replicate.h +src/Core/Reverse.h +/usr/include/eigen3/Eigen/src/Core/Reverse.h +src/Core/ArrayBase.h +/usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/Core/ArrayWrapper.h +/usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/Core/products/GeneralMatrixMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/Core/products/GeneralMatrixVector_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/Core/products/SelfadjointMatrixMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/Core/products/SelfadjointMatrixVector_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/Core/products/TriangularMatrixMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/Core/products/TriangularMatrixVector_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/Core/products/TriangularSolverMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/Core/Assign_MKL.h +/usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/Core/GlobalFunctions.h +/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +Eigen2Support +/usr/include/eigen3/Eigen/Eigen2Support + +/usr/include/eigen3/Eigen/Eigen2Support +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Eigen2Support/Macros.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/Eigen2Support/Memory.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/Eigen2Support/Meta.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/Eigen2Support/Lazy.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/Eigen2Support/Cwise.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/Eigen2Support/CwiseOperators.h +/usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/Eigen2Support/TriangularSolver.h +/usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/Eigen2Support/Block.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/Eigen2Support/VectorBlock.h +/usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/Eigen2Support/Minor.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/Eigen2Support/MathFunctions.h +/usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +iostream +- + +/usr/include/eigen3/Eigen/Eigenvalues +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +Cholesky +/usr/include/eigen3/Eigen/Cholesky +Jacobi +/usr/include/eigen3/Eigen/Jacobi +Householder +/usr/include/eigen3/Eigen/Householder +LU +/usr/include/eigen3/Eigen/LU +Geometry +/usr/include/eigen3/Eigen/Geometry +src/Eigenvalues/Tridiagonalization.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/Eigenvalues/RealSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/Eigenvalues/EigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/Eigenvalues/SelfAdjointEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/Eigenvalues/HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/Eigenvalues/ComplexSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/Eigenvalues/ComplexEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/Eigenvalues/RealQZ.h +/usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/Eigenvalues/GeneralizedEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/Eigenvalues/MatrixBaseEigenvalues.h +/usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/Eigenvalues/RealSchur_MKL.h +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/Eigenvalues/ComplexSchur_MKL.h +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Geometry +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +SVD +/usr/include/eigen3/Eigen/SVD +LU +/usr/include/eigen3/Eigen/LU +limits +- +src/Geometry/OrthoMethods.h +/usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/Geometry/EulerAngles.h +/usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/Geometry/Homogeneous.h +/usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/Geometry/RotationBase.h +/usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/Geometry/Rotation2D.h +/usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/Geometry/Quaternion.h +/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/Geometry/AngleAxis.h +/usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/Geometry/Transform.h +/usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/Geometry/Translation.h +/usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/Geometry/Scaling.h +/usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/Geometry/Hyperplane.h +/usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/Geometry/ParametrizedLine.h +/usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/Geometry/AlignedBox.h +/usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/Geometry/Umeyama.h +/usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/Geometry/arch/Geometry_SSE.h +/usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/Eigen2Support/Geometry/All.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Householder +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Householder/Householder.h +/usr/include/eigen3/Eigen/src/Householder/Householder.h +src/Householder/HouseholderSequence.h +/usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/Householder/BlockHouseholder.h +/usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Jacobi +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Jacobi/Jacobi.h +/usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/LU +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/misc/Kernel.h +/usr/include/eigen3/Eigen/src/misc/Kernel.h +src/misc/Image.h +/usr/include/eigen3/Eigen/src/misc/Image.h +src/LU/FullPivLU.h +/usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/LU/PartialPivLU.h +/usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/LU/PartialPivLU_MKL.h +/usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/LU/Determinant.h +/usr/include/eigen3/Eigen/src/LU/Determinant.h +src/LU/Inverse.h +/usr/include/eigen3/Eigen/src/LU/Inverse.h +src/LU/arch/Inverse_SSE.h +/usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/Eigen2Support/LU.h +/usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/QR +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +Cholesky +/usr/include/eigen3/Eigen/Cholesky +Jacobi +/usr/include/eigen3/Eigen/Jacobi +Householder +/usr/include/eigen3/Eigen/Householder +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/QR/HouseholderQR.h +/usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/QR/FullPivHouseholderQR.h +/usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/QR/ColPivHouseholderQR.h +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/QR/HouseholderQR_MKL.h +/usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/QR/ColPivHouseholderQR_MKL.h +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/Eigen2Support/QR.h +/usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +Eigenvalues +/usr/include/eigen3/Eigen/Eigenvalues + +/usr/include/eigen3/Eigen/SVD +QR +/usr/include/eigen3/Eigen/QR +Householder +/usr/include/eigen3/Eigen/Householder +Jacobi +/usr/include/eigen3/Eigen/Jacobi +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/SVD/JacobiSVD.h +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/SVD/JacobiSVD_MKL.h +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/SVD/UpperBidiagonalization.h +/usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/Eigen2Support/SVD.h +/usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/StdVector +Core +/usr/include/eigen3/Eigen/Core +vector +- +src/StlSupport/StdVector.h +/usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + +/usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + +/usr/include/eigen3/Eigen/src/Cholesky/LLT.h + +/usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Cholesky/Eigen/src/Core/util/MKL_support.h +iostream +- + +/usr/include/eigen3/Eigen/src/Core/Array.h + +/usr/include/eigen3/Eigen/src/Core/ArrayBase.h +../plugins/CommonCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +../plugins/MatrixCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +../plugins/ArrayCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +../plugins/CommonCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +../plugins/MatrixCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +../plugins/ArrayCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + +/usr/include/eigen3/Eigen/src/Core/Assign.h + +/usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + +/usr/include/eigen3/Eigen/src/Core/BandMatrix.h + +/usr/include/eigen3/Eigen/src/Core/Block.h + +/usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + +/usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + +/usr/include/eigen3/Eigen/src/Core/CoreIterators.h + +/usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + +/usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + +/usr/include/eigen3/Eigen/src/Core/DenseBase.h +../plugins/BlockMethods.h +/usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + +/usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + +/usr/include/eigen3/Eigen/src/Core/DenseStorage.h + +/usr/include/eigen3/Eigen/src/Core/Diagonal.h + +/usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + +/usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + +/usr/include/eigen3/Eigen/src/Core/Dot.h + +/usr/include/eigen3/Eigen/src/Core/EigenBase.h + +/usr/include/eigen3/Eigen/src/Core/Flagged.h + +/usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + +/usr/include/eigen3/Eigen/src/Core/Functors.h + +/usr/include/eigen3/Eigen/src/Core/Fuzzy.h + +/usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + +/usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + +/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + +/usr/include/eigen3/Eigen/src/Core/IO.h + +/usr/include/eigen3/Eigen/src/Core/Map.h + +/usr/include/eigen3/Eigen/src/Core/MapBase.h + +/usr/include/eigen3/Eigen/src/Core/MathFunctions.h + +/usr/include/eigen3/Eigen/src/Core/Matrix.h + +/usr/include/eigen3/Eigen/src/Core/MatrixBase.h +../plugins/CommonCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +../plugins/CommonCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +../plugins/MatrixCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +../plugins/MatrixCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/Core/NestByValue.h + +/usr/include/eigen3/Eigen/src/Core/NoAlias.h + +/usr/include/eigen3/Eigen/src/Core/NumTraits.h + +/usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + +/usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + +/usr/include/eigen3/Eigen/src/Core/ProductBase.h + +/usr/include/eigen3/Eigen/src/Core/Random.h + +/usr/include/eigen3/Eigen/src/Core/Redux.h + +/usr/include/eigen3/Eigen/src/Core/Ref.h + +/usr/include/eigen3/Eigen/src/Core/Replicate.h + +/usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + +/usr/include/eigen3/Eigen/src/Core/Reverse.h + +/usr/include/eigen3/Eigen/src/Core/Select.h + +/usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + +/usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + +/usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + +/usr/include/eigen3/Eigen/src/Core/StableNorm.h + +/usr/include/eigen3/Eigen/src/Core/Stride.h + +/usr/include/eigen3/Eigen/src/Core/Swap.h + +/usr/include/eigen3/Eigen/src/Core/Transpose.h + +/usr/include/eigen3/Eigen/src/Core/Transpositions.h + +/usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + +/usr/include/eigen3/Eigen/src/Core/VectorBlock.h + +/usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + +/usr/include/eigen3/Eigen/src/Core/Visitor.h + +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + +/usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + +/usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + +/usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + +/usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + +/usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + +/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + +/usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + +/usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + +/usr/include/eigen3/Eigen/src/Core/util/Constants.h + +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + +/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + +/usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +mkl.h +- +mkl_lapacke.h +- + +/usr/include/eigen3/Eigen/src/Core/util/Macros.h +cstdlib +- +iostream +- + +/usr/include/eigen3/Eigen/src/Core/util/Memory.h +unistd.h +- + +/usr/include/eigen3/Eigen/src/Core/util/Meta.h + +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + +/usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +limits +- +RotationBase.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +Rotation2D.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +Quaternion.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +AngleAxis.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +Transform.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +Translation.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +Scaling.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +AlignedBox.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +Hyperplane.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +ParametrizedLine.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +RotationBase.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +Rotation2D.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +Quaternion.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +AngleAxis.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +Transform.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +Translation.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +Scaling.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +AlignedBox.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +Hyperplane.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +ParametrizedLine.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/././HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/././HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +./ComplexSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +./RealSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +./RealQZ.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +./Tridiagonalization.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +./Tridiagonalization.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + +/usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + +/usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + +/usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + +/usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + +/usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + +/usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + +/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + +/usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + +/usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + +/usr/include/eigen3/Eigen/src/Geometry/Scaling.h + +/usr/include/eigen3/Eigen/src/Geometry/Transform.h + +/usr/include/eigen3/Eigen/src/Geometry/Translation.h + +/usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + +/usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + +/usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + +/usr/include/eigen3/Eigen/src/Householder/Householder.h + +/usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + +/usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + +/usr/include/eigen3/Eigen/src/LU/Determinant.h + +/usr/include/eigen3/Eigen/src/LU/FullPivLU.h + +/usr/include/eigen3/Eigen/src/LU/Inverse.h + +/usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + +/usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/LU/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/QR/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + +/usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + +/usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/QR/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/SVD/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + +/usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +Eigen/src/StlSupport/details.h +/usr/include/eigen3/Eigen/src/StlSupport/Eigen/src/StlSupport/details.h + +/usr/include/eigen3/Eigen/src/StlSupport/details.h + +/usr/include/eigen3/Eigen/src/misc/Image.h + +/usr/include/eigen3/Eigen/src/misc/Kernel.h + +/usr/include/eigen3/Eigen/src/misc/Solve.h + +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + +/usr/local/include/opencv/cxcore.h +opencv2/core/core_c.h +/usr/local/include/opencv/opencv2/core/core_c.h + +/usr/local/include/opencv2/calib3d.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/opencv2/features2d.hpp +opencv2/core/affine.hpp +/usr/local/include/opencv2/opencv2/core/affine.hpp +opencv2/calib3d/calib3d_c.h +/usr/local/include/opencv2/opencv2/calib3d/calib3d_c.h + +/usr/local/include/opencv2/calib3d/calib3d_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/calib3d/opencv2/core/core_c.h + +/usr/local/include/opencv2/core.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/opencv2/core/cvdef.h +opencv2/core/version.hpp +/usr/local/include/opencv2/opencv2/core/version.hpp +opencv2/core/base.hpp +/usr/local/include/opencv2/opencv2/core/base.hpp +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/opencv2/core/cvstd.hpp +opencv2/core/traits.hpp +/usr/local/include/opencv2/opencv2/core/traits.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/opencv2/core/matx.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/opencv2/core/types.hpp +opencv2/core/mat.hpp +/usr/local/include/opencv2/opencv2/core/mat.hpp +opencv2/core/persistence.hpp +/usr/local/include/opencv2/opencv2/core/persistence.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/opencv2/opencv.hpp +opencv2/xfeatures2d.hpp +/usr/local/include/opencv2/opencv2/xfeatures2d.hpp +opencv2/core/operations.hpp +/usr/local/include/opencv2/opencv2/core/operations.hpp +opencv2/core/cvstd.inl.hpp +/usr/local/include/opencv2/opencv2/core/cvstd.inl.hpp +opencv2/core/utility.hpp +/usr/local/include/opencv2/opencv2/core/utility.hpp +opencv2/core/optim.hpp +/usr/local/include/opencv2/opencv2/core/optim.hpp + +/usr/local/include/opencv2/core/affine.hpp +opencv2/core.hpp +- + +/usr/local/include/opencv2/core/base.hpp +climits +- +algorithm +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/core/opencv2/core/cvstd.hpp +opencv2/core/neon_utils.hpp +/usr/local/include/opencv2/core/opencv2/core/neon_utils.hpp + +/usr/local/include/opencv2/core/bufferpool.hpp + +/usr/local/include/opencv2/core/core.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/core_c.h +opencv2/core/types_c.h +/usr/local/include/opencv2/core/opencv2/core/types_c.h +cxcore.h +/usr/local/include/opencv2/core/cxcore.h +cxcore.h +/usr/local/include/opencv2/core/cxcore.h +opencv2/core/utility.hpp +/usr/local/include/opencv2/core/opencv2/core/utility.hpp + +/usr/local/include/opencv2/core/cvdef.h +limits.h +- +opencv2/core/hal/interface.h +/usr/local/include/opencv2/core/opencv2/core/hal/interface.h +emmintrin.h +- +pmmintrin.h +- +tmmintrin.h +- +smmintrin.h +- +nmmintrin.h +- +nmmintrin.h +- +popcntintrin.h +- +immintrin.h +- +immintrin.h +- +Intrin.h +- +arm_neon.h +/usr/local/include/opencv2/core/arm_neon.h +arm_neon.h +- +intrin.h +- + +/usr/local/include/opencv2/core/cvstd.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +cstddef +- +cstring +- +cctype +- +string +- +algorithm +- +utility +- +cstdlib +- +cmath +- +opencv2/core/ptr.inl.hpp +/usr/local/include/opencv2/core/opencv2/core/ptr.inl.hpp + +/usr/local/include/opencv2/core/cvstd.inl.hpp +complex +- +ostream +- + +/usr/local/include/opencv2/core/fast_math.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +fastmath.h +- +cmath +- +math.h +- +tegra_round.hpp +/usr/local/include/opencv2/core/tegra_round.hpp + +/usr/local/include/opencv2/core/hal/interface.h +cstddef +- +stddef.h +- +cstdint +- +stdint.h +- + +/usr/local/include/opencv2/core/mat.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/core/opencv2/core/matx.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/core/opencv2/core/types.hpp +opencv2/core/bufferpool.hpp +/usr/local/include/opencv2/core/opencv2/core/bufferpool.hpp +opencv2/core/mat.inl.hpp +/usr/local/include/opencv2/core/opencv2/core/mat.inl.hpp + +/usr/local/include/opencv2/core/mat.inl.hpp + +/usr/local/include/opencv2/core/matx.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/base.hpp +/usr/local/include/opencv2/core/opencv2/core/base.hpp +opencv2/core/traits.hpp +/usr/local/include/opencv2/core/opencv2/core/traits.hpp +opencv2/core/saturate.hpp +/usr/local/include/opencv2/core/opencv2/core/saturate.hpp + +/usr/local/include/opencv2/core/neon_utils.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h + +/usr/local/include/opencv2/core/operations.hpp +cstdio +- + +/usr/local/include/opencv2/core/optim.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/persistence.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/core/opencv2/core/types.hpp +opencv2/core/mat.hpp +/usr/local/include/opencv2/core/opencv2/core/mat.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/core/opencv2/opencv.hpp +time.h +- + +/usr/local/include/opencv2/core/ptr.inl.hpp +algorithm +- + +/usr/local/include/opencv2/core/saturate.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/fast_math.hpp +/usr/local/include/opencv2/core/opencv2/core/fast_math.hpp + +/usr/local/include/opencv2/core/traits.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h + +/usr/local/include/opencv2/core/types.hpp +climits +- +cfloat +- +vector +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/core/opencv2/core/cvstd.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/core/opencv2/core/matx.hpp + +/usr/local/include/opencv2/core/types_c.h +ipl.h +- +ipl/ipl.h +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +assert.h +- +stdlib.h +- +string.h +- +float.h +- +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/utility.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp +opencv2/core/core_c.h +/usr/local/include/opencv2/core/opencv2/core/core_c.h + +/usr/local/include/opencv2/core/version.hpp + +/usr/local/include/opencv2/features2d.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/flann/miniflann.hpp +/usr/local/include/opencv2/opencv2/flann/miniflann.hpp + +/usr/local/include/opencv2/features2d/features2d.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/features2d/opencv2/features2d.hpp + +/usr/local/include/opencv2/flann/config.h + +/usr/local/include/opencv2/flann/defines.h +config.h +/usr/local/include/opencv2/flann/config.h + +/usr/local/include/opencv2/flann/miniflann.hpp +opencv2/core.hpp +/usr/local/include/opencv2/flann/opencv2/core.hpp +opencv2/flann/defines.h +/usr/local/include/opencv2/flann/opencv2/flann/defines.h + +/usr/local/include/opencv2/highgui.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgcodecs.hpp +/usr/local/include/opencv2/opencv2/imgcodecs.hpp +opencv2/videoio.hpp +/usr/local/include/opencv2/opencv2/videoio.hpp +opencv2/highgui/highgui_c.h +/usr/local/include/opencv2/opencv2/highgui/highgui_c.h + +/usr/local/include/opencv2/highgui/highgui.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/highgui/opencv2/highgui.hpp + +/usr/local/include/opencv2/highgui/highgui_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/highgui/opencv2/core/core_c.h +opencv2/imgproc/imgproc_c.h +/usr/local/include/opencv2/highgui/opencv2/imgproc/imgproc_c.h +opencv2/imgcodecs/imgcodecs_c.h +/usr/local/include/opencv2/highgui/opencv2/imgcodecs/imgcodecs_c.h +opencv2/videoio/videoio_c.h +/usr/local/include/opencv2/highgui/opencv2/videoio/videoio_c.h + +/usr/local/include/opencv2/imgcodecs.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/opencv.hpp +- + +/usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/imgcodecs/opencv2/core/core_c.h + +/usr/local/include/opencv2/imgproc.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/core.hpp +- +opencv2/imgproc.hpp +- +opencv2/imgcodecs.hpp +- +opencv2/highgui.hpp +- +iostream +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +math.h +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/opencv2/highgui.hpp +opencv2/imgproc/imgproc_c.h +/usr/local/include/opencv2/opencv2/imgproc/imgproc_c.h + +/usr/local/include/opencv2/imgproc/imgproc_c.h +opencv2/imgproc/types_c.h +/usr/local/include/opencv2/imgproc/opencv2/imgproc/types_c.h + +/usr/local/include/opencv2/imgproc/types_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/imgproc/opencv2/core/core_c.h + +/usr/local/include/opencv2/ml.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +float.h +- +map +- +iostream +- + +/usr/local/include/opencv2/objdetect.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/objdetect/detection_based_tracker.hpp +/usr/local/include/opencv2/opencv2/objdetect/detection_based_tracker.hpp +opencv2/objdetect/objdetect_c.h +/usr/local/include/opencv2/opencv2/objdetect/objdetect_c.h + +/usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +vector +- + +/usr/local/include/opencv2/objdetect/objdetect_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/objdetect/opencv2/core/core_c.h +deque +- +vector +- + +/usr/local/include/opencv2/opencv.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/photo.hpp +/usr/local/include/opencv2/opencv2/photo.hpp +opencv2/video.hpp +/usr/local/include/opencv2/opencv2/video.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/opencv2/features2d.hpp +opencv2/objdetect.hpp +/usr/local/include/opencv2/opencv2/objdetect.hpp +opencv2/calib3d.hpp +/usr/local/include/opencv2/opencv2/calib3d.hpp +opencv2/imgcodecs.hpp +/usr/local/include/opencv2/opencv2/imgcodecs.hpp +opencv2/videoio.hpp +/usr/local/include/opencv2/opencv2/videoio.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/opencv2/highgui.hpp +opencv2/ml.hpp +/usr/local/include/opencv2/opencv2/ml.hpp + +/usr/local/include/opencv2/photo.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/photo/photo_c.h +/usr/local/include/opencv2/opencv2/photo/photo_c.h + +/usr/local/include/opencv2/photo/photo_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/photo/opencv2/core/core_c.h + +/usr/local/include/opencv2/video.hpp +opencv2/video/tracking.hpp +/usr/local/include/opencv2/opencv2/video/tracking.hpp +opencv2/video/background_segm.hpp +/usr/local/include/opencv2/opencv2/video/background_segm.hpp +opencv2/video/tracking_c.h +/usr/local/include/opencv2/opencv2/video/tracking_c.h + +/usr/local/include/opencv2/video/background_segm.hpp +opencv2/core.hpp +/usr/local/include/opencv2/video/opencv2/core.hpp + +/usr/local/include/opencv2/video/tracking.hpp +opencv2/core.hpp +/usr/local/include/opencv2/video/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/video/opencv2/imgproc.hpp + +/usr/local/include/opencv2/video/tracking_c.h +opencv2/imgproc/types_c.h +/usr/local/include/opencv2/video/opencv2/imgproc/types_c.h + +/usr/local/include/opencv2/videoio.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/opencv2/opencv.hpp + +/usr/local/include/opencv2/videoio/videoio_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/videoio/opencv2/core/core_c.h + +/usr/local/include/opencv2/viz.hpp +opencv2/viz/types.hpp +- +opencv2/viz/widgets.hpp +- +opencv2/viz/viz3d.hpp +- +opencv2/viz/vizcore.hpp +- + +/usr/local/include/opencv2/viz/types.hpp +string +- +opencv2/core.hpp +- +opencv2/core/affine.hpp +- + +/usr/local/include/opencv2/viz/viz3d.hpp +opencv2/core.hpp +- +opencv2/viz/types.hpp +- +opencv2/viz/widgets.hpp +- + +/usr/local/include/opencv2/viz/vizcore.hpp +opencv2/viz/types.hpp +- +opencv2/viz/widgets.hpp +- +opencv2/viz/viz3d.hpp +- + +/usr/local/include/opencv2/viz/widgets.hpp +opencv2/viz/types.hpp +- + diff --git a/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/DependInfo.cmake b/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/DependInfo.cmake new file mode 100644 index 00000000..cf5eca9e --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/DependInfo.cmake @@ -0,0 +1,26 @@ +# The set of languages for which implicit dependencies are needed: +SET(CMAKE_DEPENDS_LANGUAGES + "CXX" + ) +# The set of files for implicit dependencies of each language: +SET(CMAKE_DEPENDS_CHECK_CXX + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/test/run_vo.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/run_vo.cpp.o" + ) +SET(CMAKE_CXX_COMPILER_ID "GNU") + +# Targets to which this target links. +SET(CMAKE_TARGET_LINKED_INFO_FILES + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/src/CMakeFiles/myslam.dir/DependInfo.cmake" + ) + +# The include file search paths: +SET(CMAKE_C_TARGET_INCLUDE_PATH + "/usr/include/eigen3" + "/usr/local/include/opencv" + "/usr/local/include" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus" + "../include" + ) +SET(CMAKE_CXX_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) +SET(CMAKE_Fortran_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) +SET(CMAKE_ASM_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) diff --git a/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/build.make b/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/build.make new file mode 100644 index 00000000..cbaf9ae5 --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/build.make @@ -0,0 +1,121 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3" + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" + +# Include any dependencies generated for this target. +include test/CMakeFiles/run_vo.dir/depend.make + +# Include the progress variables for this target. +include test/CMakeFiles/run_vo.dir/progress.make + +# Include the compile flags for this target's objects. +include test/CMakeFiles/run_vo.dir/flags.make + +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: test/CMakeFiles/run_vo.dir/flags.make +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: ../test/run_vo.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles" $(CMAKE_PROGRESS_1) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object test/CMakeFiles/run_vo.dir/run_vo.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/test" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/run_vo.dir/run_vo.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/test/run_vo.cpp" + +test/CMakeFiles/run_vo.dir/run_vo.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/run_vo.dir/run_vo.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/test" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/test/run_vo.cpp" > CMakeFiles/run_vo.dir/run_vo.cpp.i + +test/CMakeFiles/run_vo.dir/run_vo.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/run_vo.dir/run_vo.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/test" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/test/run_vo.cpp" -o CMakeFiles/run_vo.dir/run_vo.cpp.s + +test/CMakeFiles/run_vo.dir/run_vo.cpp.o.requires: +.PHONY : test/CMakeFiles/run_vo.dir/run_vo.cpp.o.requires + +test/CMakeFiles/run_vo.dir/run_vo.cpp.o.provides: test/CMakeFiles/run_vo.dir/run_vo.cpp.o.requires + $(MAKE) -f test/CMakeFiles/run_vo.dir/build.make test/CMakeFiles/run_vo.dir/run_vo.cpp.o.provides.build +.PHONY : test/CMakeFiles/run_vo.dir/run_vo.cpp.o.provides + +test/CMakeFiles/run_vo.dir/run_vo.cpp.o.provides.build: test/CMakeFiles/run_vo.dir/run_vo.cpp.o + +# Object files for target run_vo +run_vo_OBJECTS = \ +"CMakeFiles/run_vo.dir/run_vo.cpp.o" + +# External object files for target run_vo +run_vo_EXTERNAL_OBJECTS = + +../bin/run_vo: test/CMakeFiles/run_vo.dir/run_vo.cpp.o +../bin/run_vo: test/CMakeFiles/run_vo.dir/build.make +../bin/run_vo: ../lib/libmyslam.so +../bin/run_vo: /usr/local/lib/libopencv_viz.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_videostab.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_superres.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_stitching.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_shape.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_video.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_photo.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_objdetect.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_calib3d.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_features2d.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_ml.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_highgui.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_videoio.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_imgcodecs.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_imgproc.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_flann.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_core.so.3.1.0 +../bin/run_vo: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build/libSophus.so +../bin/run_vo: test/CMakeFiles/run_vo.dir/link.txt + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --red --bold "Linking CXX executable ../../bin/run_vo" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/test" && $(CMAKE_COMMAND) -E cmake_link_script CMakeFiles/run_vo.dir/link.txt --verbose=$(VERBOSE) + +# Rule to build all files generated by this target. +test/CMakeFiles/run_vo.dir/build: ../bin/run_vo +.PHONY : test/CMakeFiles/run_vo.dir/build + +test/CMakeFiles/run_vo.dir/requires: test/CMakeFiles/run_vo.dir/run_vo.cpp.o.requires +.PHONY : test/CMakeFiles/run_vo.dir/requires + +test/CMakeFiles/run_vo.dir/clean: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/test" && $(CMAKE_COMMAND) -P CMakeFiles/run_vo.dir/cmake_clean.cmake +.PHONY : test/CMakeFiles/run_vo.dir/clean + +test/CMakeFiles/run_vo.dir/depend: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/test" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/test" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/DependInfo.cmake" --color=$(COLOR) +.PHONY : test/CMakeFiles/run_vo.dir/depend + diff --git a/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/cmake_clean.cmake b/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/cmake_clean.cmake new file mode 100644 index 00000000..6f7a8a1e --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/cmake_clean.cmake @@ -0,0 +1,10 @@ +FILE(REMOVE_RECURSE + "CMakeFiles/run_vo.dir/run_vo.cpp.o" + "../../bin/run_vo.pdb" + "../../bin/run_vo" +) + +# Per-language clean rules from dependency scanning. +FOREACH(lang CXX) + INCLUDE(CMakeFiles/run_vo.dir/cmake_clean_${lang}.cmake OPTIONAL) +ENDFOREACH(lang) diff --git a/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/depend.internal b/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/depend.internal new file mode 100644 index 00000000..b86410a5 --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/depend.internal @@ -0,0 +1,277 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +test/CMakeFiles/run_vo.dir/run_vo.cpp.o + ../include/myslam/camera.h + ../include/myslam/common_include.h + ../include/myslam/config.h + ../include/myslam/frame.h + ../include/myslam/map.h + ../include/myslam/mappoint.h + ../include/myslam/visual_odometry.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/test/run_vo.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/features2d/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h + /usr/local/include/opencv2/viz.hpp + /usr/local/include/opencv2/viz/types.hpp + /usr/local/include/opencv2/viz/viz3d.hpp + /usr/local/include/opencv2/viz/vizcore.hpp + /usr/local/include/opencv2/viz/widgets.hpp diff --git a/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/depend.make b/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/depend.make new file mode 100644 index 00000000..359a10de --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/depend.make @@ -0,0 +1,277 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: ../include/myslam/camera.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: ../include/myslam/common_include.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: ../include/myslam/config.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: ../include/myslam/frame.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: ../include/myslam/map.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: ../include/myslam/mappoint.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: ../include/myslam/visual_odometry.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: ../test/run_vo.cpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/Cholesky +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/Core +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/Geometry +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/Householder +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/Jacobi +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/LU +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/QR +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/SVD +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/StdVector +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv/cxcore.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/calib3d.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/affine.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/base.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/core.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/core_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/cvdef.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/mat.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/matx.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/operations.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/optim.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/traits.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/types.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/types_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/utility.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/version.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/features2d.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/features2d/features2d.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/flann/config.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/flann/defines.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/highgui.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/highgui/highgui.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/imgproc.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/ml.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/objdetect.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/opencv.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/photo.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/video.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/videoio.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/viz.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/viz/types.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/viz/viz3d.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/viz/vizcore.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/viz/widgets.hpp + diff --git a/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/flags.make b/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/flags.make new file mode 100644 index 00000000..256bd386 --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/flags.make @@ -0,0 +1,8 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# compile CXX with g++ +CXX_FLAGS = -std=c++11 -march=native -O3 -O3 -DNDEBUG -I/usr/include/eigen3 -I/usr/local/include/opencv -I/usr/local/include -I/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus -I"/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/include" + +CXX_DEFINES = + diff --git a/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/link.txt b/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/link.txt new file mode 100644 index 00000000..b3e64178 --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/link.txt @@ -0,0 +1 @@ +g++ -std=c++11 -march=native -O3 -O3 -DNDEBUG CMakeFiles/run_vo.dir/run_vo.cpp.o -o ../../bin/run_vo -rdynamic ../../lib/libmyslam.so /usr/local/lib/libopencv_viz.so.3.1.0 /usr/local/lib/libopencv_videostab.so.3.1.0 /usr/local/lib/libopencv_superres.so.3.1.0 /usr/local/lib/libopencv_stitching.so.3.1.0 /usr/local/lib/libopencv_shape.so.3.1.0 /usr/local/lib/libopencv_video.so.3.1.0 /usr/local/lib/libopencv_photo.so.3.1.0 /usr/local/lib/libopencv_objdetect.so.3.1.0 /usr/local/lib/libopencv_calib3d.so.3.1.0 /usr/local/lib/libopencv_features2d.so.3.1.0 /usr/local/lib/libopencv_ml.so.3.1.0 /usr/local/lib/libopencv_highgui.so.3.1.0 /usr/local/lib/libopencv_videoio.so.3.1.0 /usr/local/lib/libopencv_imgcodecs.so.3.1.0 /usr/local/lib/libopencv_imgproc.so.3.1.0 /usr/local/lib/libopencv_flann.so.3.1.0 /usr/local/lib/libopencv_core.so.3.1.0 /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build/libSophus.so -lg2o_core -lg2o_stuff -lg2o_types_sba -Wl,-rpath,"/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/lib:/usr/local/lib:/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build" diff --git a/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/progress.make b/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/progress.make new file mode 100644 index 00000000..c561fcae --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/progress.make @@ -0,0 +1,2 @@ +CMAKE_PROGRESS_1 = 8 + diff --git a/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/run_vo.cpp.o b/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/run_vo.cpp.o new file mode 100644 index 00000000..b856e066 Binary files /dev/null and b/vSLAM/ch9 project/0.3/build/test/CMakeFiles/run_vo.dir/run_vo.cpp.o differ diff --git a/vSLAM/ch9 project/0.3/build/test/Makefile b/vSLAM/ch9 project/0.3/build/test/Makefile new file mode 100644 index 00000000..d729c738 --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/test/Makefile @@ -0,0 +1,164 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Default target executed when no arguments are given to make. +default_target: all +.PHONY : default_target + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3" + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" + +#============================================================================= +# Targets provided globally by CMake. + +# Special rule for the target edit_cache +edit_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running interactive CMake command-line interface..." + /usr/bin/cmake -i . +.PHONY : edit_cache + +# Special rule for the target edit_cache +edit_cache/fast: edit_cache +.PHONY : edit_cache/fast + +# Special rule for the target rebuild_cache +rebuild_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake to regenerate build system..." + /usr/bin/cmake -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) +.PHONY : rebuild_cache + +# Special rule for the target rebuild_cache +rebuild_cache/fast: rebuild_cache +.PHONY : rebuild_cache/fast + +# The main all target +all: cmake_check_build_system + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/test/CMakeFiles/progress.marks" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f CMakeFiles/Makefile2 test/all + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build/CMakeFiles" 0 +.PHONY : all + +# The main clean target +clean: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f CMakeFiles/Makefile2 test/clean +.PHONY : clean + +# The main clean target +clean/fast: clean +.PHONY : clean/fast + +# Prepare targets for installation. +preinstall: all + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f CMakeFiles/Makefile2 test/preinstall +.PHONY : preinstall + +# Prepare targets for installation. +preinstall/fast: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f CMakeFiles/Makefile2 test/preinstall +.PHONY : preinstall/fast + +# clear depends +depend: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 1 +.PHONY : depend + +# Convenience name for target. +test/CMakeFiles/run_vo.dir/rule: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f CMakeFiles/Makefile2 test/CMakeFiles/run_vo.dir/rule +.PHONY : test/CMakeFiles/run_vo.dir/rule + +# Convenience name for target. +run_vo: test/CMakeFiles/run_vo.dir/rule +.PHONY : run_vo + +# fast build rule for target. +run_vo/fast: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f test/CMakeFiles/run_vo.dir/build.make test/CMakeFiles/run_vo.dir/build +.PHONY : run_vo/fast + +run_vo.o: run_vo.cpp.o +.PHONY : run_vo.o + +# target to build an object file +run_vo.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f test/CMakeFiles/run_vo.dir/build.make test/CMakeFiles/run_vo.dir/run_vo.cpp.o +.PHONY : run_vo.cpp.o + +run_vo.i: run_vo.cpp.i +.PHONY : run_vo.i + +# target to preprocess a source file +run_vo.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f test/CMakeFiles/run_vo.dir/build.make test/CMakeFiles/run_vo.dir/run_vo.cpp.i +.PHONY : run_vo.cpp.i + +run_vo.s: run_vo.cpp.s +.PHONY : run_vo.s + +# target to generate assembly for a file +run_vo.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(MAKE) -f test/CMakeFiles/run_vo.dir/build.make test/CMakeFiles/run_vo.dir/run_vo.cpp.s +.PHONY : run_vo.cpp.s + +# Help Target +help: + @echo "The following are some of the valid targets for this Makefile:" + @echo "... all (the default if no target is provided)" + @echo "... clean" + @echo "... depend" + @echo "... edit_cache" + @echo "... rebuild_cache" + @echo "... run_vo" + @echo "... run_vo.o" + @echo "... run_vo.i" + @echo "... run_vo.s" +.PHONY : help + + + +#============================================================================= +# Special targets to cleanup operation of make. + +# Special rule to run CMake to check the build system integrity. +# No rule that depends on this can have commands that come from listfiles +# because they might be regenerated. +cmake_check_build_system: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/build" && $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0 +.PHONY : cmake_check_build_system + diff --git a/vSLAM/ch9 project/0.3/build/test/cmake_install.cmake b/vSLAM/ch9 project/0.3/build/test/cmake_install.cmake new file mode 100644 index 00000000..b0c0ebb1 --- /dev/null +++ b/vSLAM/ch9 project/0.3/build/test/cmake_install.cmake @@ -0,0 +1,34 @@ +# Install script for directory: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.3/test + +# Set the install prefix +IF(NOT DEFINED CMAKE_INSTALL_PREFIX) + SET(CMAKE_INSTALL_PREFIX "/usr/local") +ENDIF(NOT DEFINED CMAKE_INSTALL_PREFIX) +STRING(REGEX REPLACE "/$" "" CMAKE_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}") + +# Set the install configuration name. +IF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + IF(BUILD_TYPE) + STRING(REGEX REPLACE "^[^A-Za-z0-9_]+" "" + CMAKE_INSTALL_CONFIG_NAME "${BUILD_TYPE}") + ELSE(BUILD_TYPE) + SET(CMAKE_INSTALL_CONFIG_NAME "Release") + ENDIF(BUILD_TYPE) + MESSAGE(STATUS "Install configuration: \"${CMAKE_INSTALL_CONFIG_NAME}\"") +ENDIF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + +# Set the component getting installed. +IF(NOT CMAKE_INSTALL_COMPONENT) + IF(COMPONENT) + MESSAGE(STATUS "Install component: \"${COMPONENT}\"") + SET(CMAKE_INSTALL_COMPONENT "${COMPONENT}") + ELSE(COMPONENT) + SET(CMAKE_INSTALL_COMPONENT) + ENDIF(COMPONENT) +ENDIF(NOT CMAKE_INSTALL_COMPONENT) + +# Install shared libraries without execute permission? +IF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + SET(CMAKE_INSTALL_SO_NO_EXE "1") +ENDIF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + diff --git a/vSLAM/ch9 project/0.3/cmake_modules/FindCSparse.cmake b/vSLAM/ch9 project/0.3/cmake_modules/FindCSparse.cmake new file mode 100644 index 00000000..f31df8de --- /dev/null +++ b/vSLAM/ch9 project/0.3/cmake_modules/FindCSparse.cmake @@ -0,0 +1,25 @@ +# Look for csparse; note the difference in the directory specifications! +FIND_PATH(CSPARSE_INCLUDE_DIR NAMES cs.h + PATHS + /usr/include/suitesparse + /usr/include + /opt/local/include + /usr/local/include + /sw/include + /usr/include/ufsparse + /opt/local/include/ufsparse + /usr/local/include/ufsparse + /sw/include/ufsparse + ) + +FIND_LIBRARY(CSPARSE_LIBRARY NAMES cxsparse + PATHS + /usr/lib + /usr/local/lib + /opt/local/lib + /sw/lib + ) + +include(FindPackageHandleStandardArgs) +find_package_handle_standard_args(CSPARSE DEFAULT_MSG + CSPARSE_INCLUDE_DIR CSPARSE_LIBRARY) diff --git a/vSLAM/ch9 project/0.3/cmake_modules/FindG2O.cmake b/vSLAM/ch9 project/0.3/cmake_modules/FindG2O.cmake new file mode 100644 index 00000000..655600fb --- /dev/null +++ b/vSLAM/ch9 project/0.3/cmake_modules/FindG2O.cmake @@ -0,0 +1,113 @@ +# Find the header files + +FIND_PATH(G2O_INCLUDE_DIR g2o/core/base_vertex.h + ${G2O_ROOT}/include + $ENV{G2O_ROOT}/include + $ENV{G2O_ROOT} + /usr/local/include + /usr/include + /opt/local/include + /sw/local/include + /sw/include + NO_DEFAULT_PATH + ) + +# Macro to unify finding both the debug and release versions of the +# libraries; this is adapted from the OpenSceneGraph FIND_LIBRARY +# macro. + +MACRO(FIND_G2O_LIBRARY MYLIBRARY MYLIBRARYNAME) + + FIND_LIBRARY("${MYLIBRARY}_DEBUG" + NAMES "g2o_${MYLIBRARYNAME}_d" + PATHS + ${G2O_ROOT}/lib/Debug + ${G2O_ROOT}/lib + $ENV{G2O_ROOT}/lib/Debug + $ENV{G2O_ROOT}/lib + NO_DEFAULT_PATH + ) + + FIND_LIBRARY("${MYLIBRARY}_DEBUG" + NAMES "g2o_${MYLIBRARYNAME}_d" + PATHS + ~/Library/Frameworks + /Library/Frameworks + /usr/local/lib + /usr/local/lib64 + /usr/lib + /usr/lib64 + /opt/local/lib + /sw/local/lib + /sw/lib + ) + + FIND_LIBRARY(${MYLIBRARY} + NAMES "g2o_${MYLIBRARYNAME}" + PATHS + ${G2O_ROOT}/lib/Release + ${G2O_ROOT}/lib + $ENV{G2O_ROOT}/lib/Release + $ENV{G2O_ROOT}/lib + NO_DEFAULT_PATH + ) + + FIND_LIBRARY(${MYLIBRARY} + NAMES "g2o_${MYLIBRARYNAME}" + PATHS + ~/Library/Frameworks + /Library/Frameworks + /usr/local/lib + /usr/local/lib64 + /usr/lib + /usr/lib64 + /opt/local/lib + /sw/local/lib + /sw/lib + ) + + IF(NOT ${MYLIBRARY}_DEBUG) + IF(MYLIBRARY) + SET(${MYLIBRARY}_DEBUG ${MYLIBRARY}) + ENDIF(MYLIBRARY) + ENDIF( NOT ${MYLIBRARY}_DEBUG) + +ENDMACRO(FIND_G2O_LIBRARY LIBRARY LIBRARYNAME) + +# Find the core elements +FIND_G2O_LIBRARY(G2O_STUFF_LIBRARY stuff) +FIND_G2O_LIBRARY(G2O_CORE_LIBRARY core) + +# Find the CLI library +FIND_G2O_LIBRARY(G2O_CLI_LIBRARY cli) + +# Find the pluggable solvers +FIND_G2O_LIBRARY(G2O_SOLVER_CHOLMOD solver_cholmod) +FIND_G2O_LIBRARY(G2O_SOLVER_CSPARSE solver_csparse) +FIND_G2O_LIBRARY(G2O_SOLVER_CSPARSE_EXTENSION csparse_extension) +FIND_G2O_LIBRARY(G2O_SOLVER_DENSE solver_dense) +FIND_G2O_LIBRARY(G2O_SOLVER_PCG solver_pcg) +FIND_G2O_LIBRARY(G2O_SOLVER_SLAM2D_LINEAR solver_slam2d_linear) +FIND_G2O_LIBRARY(G2O_SOLVER_STRUCTURE_ONLY solver_structure_only) +FIND_G2O_LIBRARY(G2O_SOLVER_EIGEN solver_eigen) + +# Find the predefined types +FIND_G2O_LIBRARY(G2O_TYPES_DATA types_data) +FIND_G2O_LIBRARY(G2O_TYPES_ICP types_icp) +FIND_G2O_LIBRARY(G2O_TYPES_SBA types_sba) +FIND_G2O_LIBRARY(G2O_TYPES_SCLAM2D types_sclam2d) +FIND_G2O_LIBRARY(G2O_TYPES_SIM3 types_sim3) +FIND_G2O_LIBRARY(G2O_TYPES_SLAM2D types_slam2d) +FIND_G2O_LIBRARY(G2O_TYPES_SLAM3D types_slam3d) + +# G2O solvers declared found if we found at least one solver +SET(G2O_SOLVERS_FOUND "NO") +IF(G2O_SOLVER_CHOLMOD OR G2O_SOLVER_CSPARSE OR G2O_SOLVER_DENSE OR G2O_SOLVER_PCG OR G2O_SOLVER_SLAM2D_LINEAR OR G2O_SOLVER_STRUCTURE_ONLY OR G2O_SOLVER_EIGEN) + SET(G2O_SOLVERS_FOUND "YES") +ENDIF(G2O_SOLVER_CHOLMOD OR G2O_SOLVER_CSPARSE OR G2O_SOLVER_DENSE OR G2O_SOLVER_PCG OR G2O_SOLVER_SLAM2D_LINEAR OR G2O_SOLVER_STRUCTURE_ONLY OR G2O_SOLVER_EIGEN) + +# G2O itself declared found if we found the core libraries and at least one solver +SET(G2O_FOUND "NO") +IF(G2O_STUFF_LIBRARY AND G2O_CORE_LIBRARY AND G2O_INCLUDE_DIR AND G2O_SOLVERS_FOUND) + SET(G2O_FOUND "YES") +ENDIF(G2O_STUFF_LIBRARY AND G2O_CORE_LIBRARY AND G2O_INCLUDE_DIR AND G2O_SOLVERS_FOUND) diff --git a/vSLAM/ch9 project/0.3/config/default.yaml b/vSLAM/ch9 project/0.3/config/default.yaml new file mode 100644 index 00000000..ae869bd4 --- /dev/null +++ b/vSLAM/ch9 project/0.3/config/default.yaml @@ -0,0 +1,30 @@ +%YAML:1.0 +# data +# the tum dataset directory, change it to yours! +dataset_dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/data + +# camera intrinsics +# fr1 +camera.fx: 517.3 +camera.fy: 516.5 +camera.cx: 325.1 +camera.cy: 249.7 + +# fr2 +#camera.fx: 520.9 +#camera.fy: 521.0 +#camera.cx: 325.1 +#camera.cy: 249.7 + +camera.depth_scale: 5000 + +# VO Parameters +number_of_features: 800 +scale_factor: 1.2 +level_pyramid: 4 +match_ratio: 2.0 +max_num_lost: 10 +min_inliers: 10 +keyframe_rotation: 0.1 +keyframe_translation: 0.1 +map_point_erase_ratio: 0.5 diff --git a/vSLAM/ch9 project/0.3/include/myslam/camera.h b/vSLAM/ch9 project/0.3/include/myslam/camera.h new file mode 100644 index 00000000..bace0652 --- /dev/null +++ b/vSLAM/ch9 project/0.3/include/myslam/camera.h @@ -0,0 +1,51 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifndef CAMERA_H +#define CAMERA_H + +#include "myslam/common_include.h" + +namespace myslam +{ + +// Pinhole RGBD camera model +class Camera +{ +public: + typedef std::shared_ptr Ptr; + float fx_, fy_, cx_, cy_, depth_scale_; + + Camera(); + Camera ( float fx, float fy, float cx, float cy, float depth_scale=0 ) : + fx_ ( fx ), fy_ ( fy ), cx_ ( cx ), cy_ ( cy ), depth_scale_ ( depth_scale ) + {} + + // coordinate transform: world, camera, pixel + Vector3d world2camera( const Vector3d& p_w, const SE3& T_c_w ); + Vector3d camera2world( const Vector3d& p_c, const SE3& T_c_w ); + Vector2d camera2pixel( const Vector3d& p_c ); + Vector3d pixel2camera( const Vector2d& p_p, double depth=1 ); + Vector3d pixel2world ( const Vector2d& p_p, const SE3& T_c_w, double depth=1 ); + Vector2d world2pixel ( const Vector3d& p_w, const SE3& T_c_w ); + +}; + +} +#endif // CAMERA_H diff --git a/vSLAM/ch9 project/0.3/include/myslam/common_include.h b/vSLAM/ch9 project/0.3/include/myslam/common_include.h new file mode 100644 index 00000000..a8f7e4cd --- /dev/null +++ b/vSLAM/ch9 project/0.3/include/myslam/common_include.h @@ -0,0 +1,52 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + + +#ifndef COMMON_INCLUDE_H +#define COMMON_INCLUDE_H + +// define the commonly included file to avoid a long include list +// for Eigen +#include +#include +using Eigen::Vector2d; +using Eigen::Vector3d; + +// for Sophus +#include +#include +using Sophus::SO3; +using Sophus::SE3; + +// for cv +#include +using cv::Mat; + +// std +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace std; +#endif \ No newline at end of file diff --git a/vSLAM/ch9 project/0.3/include/myslam/config.h b/vSLAM/ch9 project/0.3/include/myslam/config.h new file mode 100644 index 00000000..f5c7b452 --- /dev/null +++ b/vSLAM/ch9 project/0.3/include/myslam/config.h @@ -0,0 +1,49 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifndef CONFIG_H +#define CONFIG_H + +#include "myslam/common_include.h" + +namespace myslam +{ +class Config +{ +private: + static std::shared_ptr config_; + cv::FileStorage file_; + + Config () {} // private constructor makes a singleton +public: + ~Config(); // close the file when deconstructing + + // set a new config file + static void setParameterFile( const std::string& filename ); + + // access the parameter values + template< typename T > + static T get( const std::string& key ) + { + return T( Config::config_->file_[key] ); + } +}; +} + +#endif // CONFIG_H diff --git a/vSLAM/ch9 project/0.3/include/myslam/frame.h b/vSLAM/ch9 project/0.3/include/myslam/frame.h new file mode 100644 index 00000000..e0d4ce48 --- /dev/null +++ b/vSLAM/ch9 project/0.3/include/myslam/frame.h @@ -0,0 +1,65 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifndef FRAME_H +#define FRAME_H + +#include "myslam/common_include.h" +#include "myslam/camera.h" + +namespace myslam +{ + +// forward declare +class MapPoint; +class Frame +{ +public: + typedef std::shared_ptr Ptr; + unsigned long id_; // id of this frame + double time_stamp_; // when it is recorded + SE3 T_c_w_; // transform from world to camera + Camera::Ptr camera_; // Pinhole RGBD Camera model + Mat color_, depth_; // color and depth image + // std::vector keypoints_; // key points in image + // std::vector map_points_; // associated map points + bool is_key_frame_; // whether a key-frame + +public: // data members + Frame(); + Frame( long id, double time_stamp=0, SE3 T_c_w=SE3(), Camera::Ptr camera=nullptr, Mat color=Mat(), Mat depth=Mat() ); + ~Frame(); + + static Frame::Ptr createFrame(); + + // find the depth in depth map + double findDepth( const cv::KeyPoint& kp ); + + // Get Camera Center + Vector3d getCamCenter() const; + + void setPose( const SE3& T_c_w ); + + // check if a point is in this frame + bool isInFrame( const Vector3d& pt_world ); +}; + +} + +#endif // FRAME_H diff --git a/vSLAM/ch9 project/0.3/include/myslam/g2o_types.h b/vSLAM/ch9 project/0.3/include/myslam/g2o_types.h new file mode 100644 index 00000000..5097268b --- /dev/null +++ b/vSLAM/ch9 project/0.3/include/myslam/g2o_types.h @@ -0,0 +1,82 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifndef MYSLAM_G2O_TYPES_H//防止头文件重复引用 +#define MYSLAM_G2O_TYPES_H//宏定义 + +#include "myslam/common_include.h"//常用的头文件 放在一起 化繁为简 +#include "camera.h" + +#include +#include +#include +#include +#include +#include +#include +#include +/*使用非线性优化求解相机位姿态*/ +namespace myslam//命令空间下 防止定义的出其他库里的同名函数 +{ + //边 +class EdgeProjectXYZRGBD : public g2o::BaseBinaryEdge<3, Eigen::Vector3d, g2o::VertexSBAPointXYZ, g2o::VertexSE3Expmap> +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW; + virtual void computeError();//计算误差 + virtual void linearizeOplus();//雅克比矩阵 + virtual bool read( std::istream& in ){} + virtual bool write( std::ostream& out) const {} + +}; + +// only to optimize the pose, no point +class EdgeProjectXYZRGBDPoseOnly: public g2o::BaseUnaryEdge<3, Eigen::Vector3d, g2o::VertexSE3Expmap > +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + // Error: measure = R*point+t + virtual void computeError(); + virtual void linearizeOplus(); + + virtual bool read( std::istream& in ){} + virtual bool write( std::ostream& out) const {} + + Vector3d point_; +}; + +class EdgeProjectXYZ2UVPoseOnly: public g2o::BaseUnaryEdge<2, Eigen::Vector2d, g2o::VertexSE3Expmap > +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + virtual void computeError(); + virtual void linearizeOplus(); + + virtual bool read( std::istream& in ){} + virtual bool write(std::ostream& os) const {}; + + Vector3d point_; + Camera* camera_; +}; + +} + + +#endif // MYSLAM_G2O_TYPES_H diff --git a/vSLAM/ch9 project/0.3/include/myslam/map.h b/vSLAM/ch9 project/0.3/include/myslam/map.h new file mode 100644 index 00000000..f37547ca --- /dev/null +++ b/vSLAM/ch9 project/0.3/include/myslam/map.h @@ -0,0 +1,43 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifndef MAP_H +#define MAP_H + +#include "myslam/common_include.h" +#include "myslam/frame.h" +#include "myslam/mappoint.h" + +namespace myslam +{ +class Map +{ +public: + typedef shared_ptr Ptr; + unordered_map map_points_; // all landmarks + unordered_map keyframes_; // all key-frames + + Map() {} + + void insertKeyFrame( Frame::Ptr frame ); + void insertMapPoint( MapPoint::Ptr map_point ); +}; +} + +#endif // MAP_H diff --git a/vSLAM/ch9 project/0.3/include/myslam/mappoint.h b/vSLAM/ch9 project/0.3/include/myslam/mappoint.h new file mode 100644 index 00000000..67645942 --- /dev/null +++ b/vSLAM/ch9 project/0.3/include/myslam/mappoint.h @@ -0,0 +1,49 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifndef MAPPOINT_H +#define MAPPOINT_H + +namespace myslam +{ + +class Frame; +class MapPoint +{ +public: + typedef shared_ptr Ptr; + unsigned long id_; // ID + bool good_; // wheter a good point + Vector3d pos_; // Position in world + Vector3d norm_; // Normal of viewing direction + Mat descriptor_; // Descriptor for matching + + list observed_frames_; // frames that can observe this point + + int observed_times_; // being observed by feature matching algo. + int matched_times_; // being an inliner in pose estimation + + MapPoint(); + MapPoint( long id, Vector3d position, Vector3d norm ); + + static MapPoint::Ptr createMapPoint(); +}; +} + +#endif // MAPPOINT_H diff --git a/vSLAM/ch9 project/0.3/include/myslam/visual_odometry.h b/vSLAM/ch9 project/0.3/include/myslam/visual_odometry.h new file mode 100644 index 00000000..4cf5aeaf --- /dev/null +++ b/vSLAM/ch9 project/0.3/include/myslam/visual_odometry.h @@ -0,0 +1,90 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifndef VISUALODOMETRY_H +#define VISUALODOMETRY_H + +#include "myslam/common_include.h" +#include "myslam/map.h" + +#include + +namespace myslam +{ +class VisualOdometry +{ +public: + typedef shared_ptr Ptr; + enum VOState { + INITIALIZING=-1, + OK=0, + LOST + }; + + VOState state_; // current VO status + Map::Ptr map_; // map with all frames and map points + + Frame::Ptr ref_; // reference key-frame + Frame::Ptr curr_; // current frame + + cv::Ptr orb_; // orb detector and computer + vector pts_3d_ref_; // 3d points in reference frame + vector keypoints_curr_; // keypoints in current frame + Mat descriptors_curr_; // descriptor in current frame + Mat descriptors_ref_; // descriptor in reference frame + vector feature_matches_; // feature matches + cv::FlannBasedMatcher matcher_flann_; // flann matcher + + SE3 T_c_r_estimated_; // the estimated pose of current frame + int num_inliers_; // number of inlier features in icp + int num_lost_; // number of lost times + + // parameters + int num_of_features_; // number of features + double scale_factor_; // scale in image pyramid + int level_pyramid_; // number of pyramid levels + float match_ratio_; // ratio for selecting good matches + int max_num_lost_; // max number of continuous lost times + int min_inliers_; // minimum inliers + double key_frame_min_rot; // minimal rotation of two key-frames + double key_frame_min_trans; // minimal translation of two key-frames + double map_point_erase_ratio_; // remove map point ratio + +public: // functions + VisualOdometry(); + ~VisualOdometry(); + + bool addFrame( Frame::Ptr frame ); // add a new frame + +protected: + // inner operation + void extractKeyPoints(); + void computeDescriptors(); + void featureMatching(); + void setRef3DPoints(); + void poseEstimationPnP(); + + void addKeyFrame(); + bool checkEstimatedPose(); + bool checkKeyFrame(); + +}; +} + +#endif // VISUALODOMETRY_H diff --git a/vSLAM/ch9 project/0.3/lib/liblibmyslam.a b/vSLAM/ch9 project/0.3/lib/liblibmyslam.a new file mode 100644 index 00000000..46f62f98 Binary files /dev/null and b/vSLAM/ch9 project/0.3/lib/liblibmyslam.a differ diff --git a/vSLAM/ch9 project/0.3/lib/libmyslam.so b/vSLAM/ch9 project/0.3/lib/libmyslam.so new file mode 100755 index 00000000..a9af42f6 Binary files /dev/null and b/vSLAM/ch9 project/0.3/lib/libmyslam.so differ diff --git a/vSLAM/ch9 project/0.3/src/CMakeLists.txt b/vSLAM/ch9 project/0.3/src/CMakeLists.txt new file mode 100644 index 00000000..07355f17 --- /dev/null +++ b/vSLAM/ch9 project/0.3/src/CMakeLists.txt @@ -0,0 +1,13 @@ +add_library( myslam SHARED + frame.cpp + mappoint.cpp + map.cpp + camera.cpp + config.cpp + g2o_types.cpp + visual_odometry.cpp +) + +target_link_libraries( myslam + ${THIRD_PARTY_LIBS} +) \ No newline at end of file diff --git a/vSLAM/ch9 project/0.3/src/camera.cpp b/vSLAM/ch9 project/0.3/src/camera.cpp new file mode 100644 index 00000000..d79d63eb --- /dev/null +++ b/vSLAM/ch9 project/0.3/src/camera.cpp @@ -0,0 +1,73 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "myslam/camera.h" +#include + +namespace myslam +{ + +Camera::Camera() +{ + fx_ = Config::get("camera.fx"); + fy_ = Config::get("camera.fy"); + cx_ = Config::get("camera.cx"); + cy_ = Config::get("camera.cy"); + depth_scale_ = Config::get("camera.depth_scale"); +} + +Vector3d Camera::world2camera ( const Vector3d& p_w, const SE3& T_c_w ) +{ + return T_c_w*p_w; +} + +Vector3d Camera::camera2world ( const Vector3d& p_c, const SE3& T_c_w ) +{ + return T_c_w.inverse() *p_c; +} + +Vector2d Camera::camera2pixel ( const Vector3d& p_c ) +{ + return Vector2d ( + fx_ * p_c ( 0,0 ) / p_c ( 2,0 ) + cx_, + fy_ * p_c ( 1,0 ) / p_c ( 2,0 ) + cy_ + ); +} + +Vector3d Camera::pixel2camera ( const Vector2d& p_p, double depth ) +{ + return Vector3d ( + ( p_p ( 0,0 )-cx_ ) *depth/fx_, + ( p_p ( 1,0 )-cy_ ) *depth/fy_, + depth + ); +} + +Vector2d Camera::world2pixel ( const Vector3d& p_w, const SE3& T_c_w ) +{ + return camera2pixel ( world2camera(p_w, T_c_w) ); +} + +Vector3d Camera::pixel2world ( const Vector2d& p_p, const SE3& T_c_w, double depth ) +{ + return camera2world ( pixel2camera ( p_p, depth ), T_c_w ); +} + + +} diff --git a/vSLAM/ch9 project/0.3/src/config.cpp b/vSLAM/ch9 project/0.3/src/config.cpp new file mode 100644 index 00000000..9817d8d5 --- /dev/null +++ b/vSLAM/ch9 project/0.3/src/config.cpp @@ -0,0 +1,46 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "myslam/config.h" + +namespace myslam +{ + +void Config::setParameterFile( const std::string& filename ) +{ + if ( config_ == nullptr ) + config_ = shared_ptr(new Config); + config_->file_ = cv::FileStorage( filename.c_str(), cv::FileStorage::READ ); + if ( config_->file_.isOpened() == false ) + { + std::cerr<<"parameter file "<file_.release(); + return; + } +} + +Config::~Config() +{ + if ( file_.isOpened() ) + file_.release(); +} + +shared_ptr Config::config_ = nullptr; + +} diff --git a/vSLAM/ch9 project/0.3/src/frame.cpp b/vSLAM/ch9 project/0.3/src/frame.cpp new file mode 100644 index 00000000..c0c118c9 --- /dev/null +++ b/vSLAM/ch9 project/0.3/src/frame.cpp @@ -0,0 +1,96 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "myslam/frame.h" + +namespace myslam +{ +Frame::Frame() +: id_(-1), time_stamp_(-1), camera_(nullptr), is_key_frame_(false) +{ + +} + +Frame::Frame ( long id, double time_stamp, SE3 T_c_w, Camera::Ptr camera, Mat color, Mat depth ) +: id_(id), time_stamp_(time_stamp), T_c_w_(T_c_w), camera_(camera), color_(color), depth_(depth), is_key_frame_(false) +{ + +} + +Frame::~Frame() +{ + +} + +Frame::Ptr Frame::createFrame() +{ + static long factory_id = 0; + return Frame::Ptr( new Frame(factory_id++) ); +} + +double Frame::findDepth ( const cv::KeyPoint& kp ) +{ + int x = cvRound(kp.pt.x); + int y = cvRound(kp.pt.y); + ushort d = depth_.ptr(y)[x]; + if ( d!=0 ) + { + return double(d)/camera_->depth_scale_; + } + else + { + // check the nearby points + int dx[4] = {-1,0,1,0}; + int dy[4] = {0,-1,0,1}; + for ( int i=0; i<4; i++ ) + { + d = depth_.ptr( y+dy[i] )[x+dx[i]]; + if ( d!=0 ) + { + return double(d)/camera_->depth_scale_; + } + } + } + return -1.0; +} + +void Frame::setPose ( const SE3& T_c_w ) +{ + T_c_w_ = T_c_w; +} + + +Vector3d Frame::getCamCenter() const +{ + return T_c_w_.inverse().translation(); +} + +bool Frame::isInFrame ( const Vector3d& pt_world ) +{ + Vector3d p_cam = camera_->world2camera( pt_world, T_c_w_ ); + // cout<<"P_cam = "<world2pixel( pt_world, T_c_w_ ); + // cout<<"P_pixel = "<0 && pixel(1,0)>0 + && pixel(0,0) ( _vertices[0] ); + const g2o::VertexSE3Expmap* pose = static_cast ( _vertices[1] ); + _error = _measurement - pose->estimate().map ( point->estimate() ); +} +//雅克比矩阵计算 +void EdgeProjectXYZRGBD::linearizeOplus() +{ + g2o::VertexSE3Expmap* pose = static_cast ( _vertices[1] ); + g2o::SE3Quat T ( pose->estimate() ); + g2o::VertexSBAPointXYZ* point = static_cast ( _vertices[0] ); + Eigen::Vector3d xyz = point->estimate(); + Eigen::Vector3d xyz_trans = T.map ( xyz ); + double x = xyz_trans[0]; + double y = xyz_trans[1]; + double z = xyz_trans[2]; + + _jacobianOplusXi = - T.rotation().toRotationMatrix(); + + _jacobianOplusXj ( 0,0 ) = 0; + _jacobianOplusXj ( 0,1 ) = -z; + _jacobianOplusXj ( 0,2 ) = y; + _jacobianOplusXj ( 0,3 ) = -1; + _jacobianOplusXj ( 0,4 ) = 0; + _jacobianOplusXj ( 0,5 ) = 0; + + _jacobianOplusXj ( 1,0 ) = z; + _jacobianOplusXj ( 1,1 ) = 0; + _jacobianOplusXj ( 1,2 ) = -x; + _jacobianOplusXj ( 1,3 ) = 0; + _jacobianOplusXj ( 1,4 ) = -1; + _jacobianOplusXj ( 1,5 ) = 0; + + _jacobianOplusXj ( 2,0 ) = -y; + _jacobianOplusXj ( 2,1 ) = x; + _jacobianOplusXj ( 2,2 ) = 0; + _jacobianOplusXj ( 2,3 ) = 0; + _jacobianOplusXj ( 2,4 ) = 0; + _jacobianOplusXj ( 2,5 ) = -1; +} + //投影误差计算 +void EdgeProjectXYZRGBDPoseOnly::computeError() +{ + const g2o::VertexSE3Expmap* pose = static_cast ( _vertices[0] ); + _error = _measurement - pose->estimate().map ( point_ ); +} +//雅克比矩阵计算 +void EdgeProjectXYZRGBDPoseOnly::linearizeOplus() +{ + g2o::VertexSE3Expmap* pose = static_cast ( _vertices[0] ); + g2o::SE3Quat T ( pose->estimate() ); + Vector3d xyz_trans = T.map ( point_ ); + double x = xyz_trans[0]; + double y = xyz_trans[1]; + double z = xyz_trans[2]; + + _jacobianOplusXi ( 0,0 ) = 0; + _jacobianOplusXi ( 0,1 ) = -z; + _jacobianOplusXi ( 0,2 ) = y; + _jacobianOplusXi ( 0,3 ) = -1; + _jacobianOplusXi ( 0,4 ) = 0; + _jacobianOplusXi ( 0,5 ) = 0; + + _jacobianOplusXi ( 1,0 ) = z; + _jacobianOplusXi ( 1,1 ) = 0; + _jacobianOplusXi ( 1,2 ) = -x; + _jacobianOplusXi ( 1,3 ) = 0; + _jacobianOplusXi ( 1,4 ) = -1; + _jacobianOplusXi ( 1,5 ) = 0; + + _jacobianOplusXi ( 2,0 ) = -y; + _jacobianOplusXi ( 2,1 ) = x; + _jacobianOplusXi ( 2,2 ) = 0; + _jacobianOplusXi ( 2,3 ) = 0; + _jacobianOplusXi ( 2,4 ) = 0; + _jacobianOplusXi ( 2,5 ) = -1; +} + //投影误差计算 +void EdgeProjectXYZ2UVPoseOnly::computeError() +{ + const g2o::VertexSE3Expmap* pose = static_cast ( _vertices[0] ); + _error = _measurement - camera_->camera2pixel ( + pose->estimate().map(point_) ); +} +//雅克比矩阵计算 +void EdgeProjectXYZ2UVPoseOnly::linearizeOplus() +{ + g2o::VertexSE3Expmap* pose = static_cast ( _vertices[0] ); + g2o::SE3Quat T ( pose->estimate() ); + Vector3d xyz_trans = T.map ( point_ ); + double x = xyz_trans[0]; + double y = xyz_trans[1]; + double z = xyz_trans[2]; + double z_2 = z*z; + + _jacobianOplusXi ( 0,0 ) = x*y/z_2 *camera_->fx_; + _jacobianOplusXi ( 0,1 ) = - ( 1+ ( x*x/z_2 ) ) *camera_->fx_; + _jacobianOplusXi ( 0,2 ) = y/z * camera_->fx_; + _jacobianOplusXi ( 0,3 ) = -1./z * camera_->fx_; + _jacobianOplusXi ( 0,4 ) = 0; + _jacobianOplusXi ( 0,5 ) = x/z_2 * camera_->fx_; + + _jacobianOplusXi ( 1,0 ) = ( 1+y*y/z_2 ) *camera_->fy_; + _jacobianOplusXi ( 1,1 ) = -x*y/z_2 *camera_->fy_; + _jacobianOplusXi ( 1,2 ) = -x/z *camera_->fy_; + _jacobianOplusXi ( 1,3 ) = 0; + _jacobianOplusXi ( 1,4 ) = -1./z *camera_->fy_; + _jacobianOplusXi ( 1,5 ) = y/z_2 *camera_->fy_; +} + + +} diff --git a/vSLAM/ch9 project/0.3/src/map.cpp b/vSLAM/ch9 project/0.3/src/map.cpp new file mode 100644 index 00000000..21faca53 --- /dev/null +++ b/vSLAM/ch9 project/0.3/src/map.cpp @@ -0,0 +1,51 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "myslam/map.h" + +namespace myslam +{ + +void Map::insertKeyFrame ( Frame::Ptr frame ) +{ + cout<<"Key frame size = "<id_) == keyframes_.end() ) + { + keyframes_.insert( make_pair(frame->id_, frame) ); + } + else + { + keyframes_[ frame->id_ ] = frame; + } +} + +void Map::insertMapPoint ( MapPoint::Ptr map_point ) +{ + if ( map_points_.find(map_point->id_) == map_points_.end() ) + { + map_points_.insert( make_pair(map_point->id_, map_point) ); + } + else + { + map_points_[map_point->id_] = map_point; + } +} + + +} diff --git a/vSLAM/ch9 project/0.3/src/mappoint.cpp b/vSLAM/ch9 project/0.3/src/mappoint.cpp new file mode 100644 index 00000000..b03b5137 --- /dev/null +++ b/vSLAM/ch9 project/0.3/src/mappoint.cpp @@ -0,0 +1,46 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "myslam/common_include.h" +#include "myslam/mappoint.h" + +namespace myslam +{ + +MapPoint::MapPoint() +: id_(-1), pos_(Vector3d(0,0,0)), norm_(Vector3d(0,0,0)), good_(true), observed_times_(0) +{ + +} + +MapPoint::MapPoint ( long id, Vector3d position, Vector3d norm ) +: id_(id), pos_(position), norm_(norm), good_(true), observed_times_(0) +{ + +} + +MapPoint::Ptr MapPoint::createMapPoint() +{ + static long factory_id = 0; + return MapPoint::Ptr( + new MapPoint( factory_id++, Vector3d(0,0,0), Vector3d(0,0,0) ) + ); +} + +} diff --git a/vSLAM/ch9 project/0.3/src/visual_odometry.cpp b/vSLAM/ch9 project/0.3/src/visual_odometry.cpp new file mode 100644 index 00000000..35f4d4c3 --- /dev/null +++ b/vSLAM/ch9 project/0.3/src/visual_odometry.cpp @@ -0,0 +1,268 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +/*在求解相机位姿之后使用非线性图优化*/ +#include +#include +#include +#include +#include + +#include "myslam/config.h" +#include "myslam/visual_odometry.h" +#include "myslam/g2o_types.h" + +namespace myslam +{ + +VisualOdometry::VisualOdometry() : + state_ ( INITIALIZING ), ref_ ( nullptr ), curr_ ( nullptr ), map_ ( new Map ), num_lost_ ( 0 ), num_inliers_ ( 0 ), matcher_flann_( new cv::flann::LshIndexParams(5,10,2) ) +{ + num_of_features_ = Config::get ( "number_of_features" ); + scale_factor_ = Config::get ( "scale_factor" ); + level_pyramid_ = Config::get ( "level_pyramid" ); + match_ratio_ = Config::get ( "match_ratio" ); + max_num_lost_ = Config::get ( "max_num_lost" ); + min_inliers_ = Config::get ( "min_inliers" ); + key_frame_min_rot = Config::get ( "keyframe_rotation" ); + key_frame_min_trans = Config::get ( "keyframe_translation" ); + map_point_erase_ratio_ = Config::get ("map_point_erase_ratio"); + orb_ = cv::ORB::create ( num_of_features_, scale_factor_, level_pyramid_ ); +} + +VisualOdometry::~VisualOdometry() +{ + +} + +bool VisualOdometry::addFrame ( Frame::Ptr frame ) +{ + switch ( state_ ) + { + case INITIALIZING: + { + state_ = OK; + curr_ = ref_ = frame; + map_->insertKeyFrame ( frame ); + // extract features from first frame and add them into map + extractKeyPoints(); + computeDescriptors(); + setRef3DPoints(); + break; + } + case OK: + { + curr_ = frame; + extractKeyPoints(); + computeDescriptors(); + featureMatching(); + poseEstimationPnP();//位置估计 加入非线性优化算法 + if ( checkEstimatedPose() == true ) // a good estimation + { + curr_->T_c_w_ = T_c_r_estimated_ * ref_->T_c_w_; // T_c_w = T_c_r*T_r_w + ref_ = curr_; + setRef3DPoints(); + num_lost_ = 0; + if ( checkKeyFrame() == true ) // is a key-frame + { + addKeyFrame(); + } + } + else // bad estimation due to various reasons + { + num_lost_++; + if ( num_lost_ > max_num_lost_ ) + { + state_ = LOST; + } + return false; + } + break; + } + case LOST: + { + cout<<"vo has lost."<detect ( curr_->color_, keypoints_curr_ ); + cout<<"extract keypoints cost time: "<compute ( curr_->color_, keypoints_curr_, descriptors_curr_ ); + cout<<"descriptor computation cost time: "< matches; + matcher_flann_.match( descriptors_ref_, descriptors_curr_, matches ); + // select the best matches + float min_dis = std::min_element ( + matches.begin(), matches.end(), + [] ( const cv::DMatch& m1, const cv::DMatch& m2 ) + { + return m1.distance < m2.distance; + } )->distance; + + feature_matches_.clear(); + for ( cv::DMatch& m : matches ) + { + if ( m.distance < max ( min_dis*match_ratio_, 30.0 ) ) + { + feature_matches_.push_back(m); + } + } + cout<<"good matches: "<findDepth(keypoints_curr_[i]); + if ( d > 0) + { + Vector3d p_cam = ref_->camera_->pixel2camera( + Vector2d(keypoints_curr_[i].pt.x, keypoints_curr_[i].pt.y), d + ); + pts_3d_ref_.push_back( cv::Point3f( p_cam(0,0), p_cam(1,0), p_cam(2,0) )); + descriptors_ref_.push_back(descriptors_curr_.row(i)); + } + } +} + +//位置估计 加入非线性优化算法 +void VisualOdometry::poseEstimationPnP() +{ + // construct the 3d 2d observations + vector pts3d; + vector pts2d; + + for ( cv::DMatch m:feature_matches_ ) + { + pts3d.push_back( pts_3d_ref_[m.queryIdx] ); + pts2d.push_back( keypoints_curr_[m.trainIdx].pt ); + } + + Mat K = ( cv::Mat_(3,3)<< + ref_->camera_->fx_, 0, ref_->camera_->cx_, + 0, ref_->camera_->fy_, ref_->camera_->cy_, + 0,0,1 + ); + Mat rvec, tvec, inliers; + cv::solvePnPRansac( pts3d, pts2d, K, Mat(), rvec, tvec, false, 100, 4.0, 0.99, inliers ); + num_inliers_ = inliers.rows; + cout<<"pnp inliers: "<(0,0), rvec.at(1,0), rvec.at(2,0)), + Vector3d( tvec.at(0,0), tvec.at(1,0), tvec.at(2,0)) + ); + + //在上述PNP求解之后加入图优化 + // using bundle adjustment to optimize the pose + typedef g2o::BlockSolver> Block; + Block::LinearSolverType* linearSolver = new g2o::LinearSolverDense(); + Block* solver_ptr = new Block( linearSolver ); + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg ( solver_ptr ); + g2o::SparseOptimizer optimizer; + optimizer.setAlgorithm ( solver );//非线性优化器 + + g2o::VertexSE3Expmap* pose = new g2o::VertexSE3Expmap(); + pose->setId ( 0 ); + pose->setEstimate ( g2o::SE3Quat ( + T_c_r_estimated_.rotation_matrix(), + T_c_r_estimated_.translation() + ) ); + optimizer.addVertex ( pose );//加入优化列队 + + // 边 edges + for ( int i=0; i(i,0); + // 3D -> 2D projection + EdgeProjectXYZ2UVPoseOnly* edge = new EdgeProjectXYZ2UVPoseOnly(); + edge->setId(i); + edge->setVertex(0, pose); + edge->camera_ = curr_->camera_.get(); + edge->point_ = Vector3d( pts3d[index].x, pts3d[index].y, pts3d[index].z ); + edge->setMeasurement( Vector2d(pts2d[index].x, pts2d[index].y) ); + edge->setInformation( Eigen::Matrix2d::Identity() ); + optimizer.addEdge( edge );//添加边 + } + + optimizer.initializeOptimization();//初始化优化器 + optimizer.optimize(10);//执行10次优化 + + T_c_r_estimated_ = SE3 ( + pose->estimate().rotation(), + pose->estimate().translation() + ); +} +//检查估计的位姿 +bool VisualOdometry::checkEstimatedPose() +{ + // check if the estimated pose is good + if ( num_inliers_ < min_inliers_ ) + { + cout<<"reject because inlier is too small: "< 5.0 ) + { + cout<<"reject because motion is too large: "<(); + Vector3d rot = d.tail<3>(); + if ( rot.norm() >key_frame_min_rot || trans.norm() >key_frame_min_trans ) + return true; + return false; +} + +void VisualOdometry::addKeyFrame() +{ + cout<<"adding a key-frame"<insertKeyFrame ( curr_ ); +} + +} diff --git a/vSLAM/ch9 project/0.3/test/CMakeLists.txt b/vSLAM/ch9 project/0.3/test/CMakeLists.txt new file mode 100644 index 00000000..241c4599 --- /dev/null +++ b/vSLAM/ch9 project/0.3/test/CMakeLists.txt @@ -0,0 +1,2 @@ +add_executable( run_vo run_vo.cpp ) +target_link_libraries( run_vo myslam ) \ No newline at end of file diff --git a/vSLAM/ch9 project/0.3/test/run_vo.cpp b/vSLAM/ch9 project/0.3/test/run_vo.cpp new file mode 100644 index 00000000..8fe65c39 --- /dev/null +++ b/vSLAM/ch9 project/0.3/test/run_vo.cpp @@ -0,0 +1,100 @@ +// -------------- test the visual odometry ------------- +#include +#include +#include +#include +#include + +#include "myslam/config.h" +#include "myslam/visual_odometry.h" + +int main ( int argc, char** argv ) +{ + if ( argc != 2 ) + { + cout<<"usage: run_vo parameter_file"< ( "dataset_dir" ); + cout<<"dataset: "< rgb_files, depth_files; + vector rgb_times, depth_times; + while ( !fin.eof() )//读取数据集列表 + { + string rgb_time, rgb_file, depth_time, depth_file; + fin>>rgb_time>>rgb_file>>depth_time>>depth_file; + rgb_times.push_back ( atof ( rgb_time.c_str() ) ); + depth_times.push_back ( atof ( depth_time.c_str() ) ); + rgb_files.push_back ( dataset_dir+"/"+rgb_file ); + depth_files.push_back ( dataset_dir+"/"+depth_file ); + + if ( fin.good() == false ) + break; + } + + myslam::Camera::Ptr camera ( new myslam::Camera ); + + // visualization 可视化 + cv::viz::Viz3d vis("Visual Odometry"); + cv::viz::WCoordinateSystem world_coor(1.0), camera_coor(0.5); + cv::Point3d cam_pos( 0, -1.0, -1.0 ), cam_focal_point(0,0,0), cam_y_dir(0,1,0); + cv::Affine3d cam_pose = cv::viz::makeCameraPose( cam_pos, cam_focal_point, cam_y_dir ); + vis.setViewerPose( cam_pose ); + + world_coor.setRenderingProperty(cv::viz::LINE_WIDTH, 2.0); + camera_coor.setRenderingProperty(cv::viz::LINE_WIDTH, 1.0); + vis.showWidget( "World", world_coor ); + vis.showWidget( "Camera", camera_coor ); + + cout<<"read total "<camera_ = camera; + pFrame->color_ = color; + pFrame->depth_ = depth; + pFrame->time_stamp_ = rgb_times[i]; + + boost::timer timer; + vo->addFrame ( pFrame ); + cout<<"VO costs time: "<state_ == myslam::VisualOdometry::LOST ) + break; + SE3 Tcw = pFrame->T_c_w_.inverse(); + + // show the map and the camera pose 照相机位姿 + cv::Affine3d M(//相机位姿 + cv::Affine3d::Mat3( + Tcw.rotation_matrix()(0,0), Tcw.rotation_matrix()(0,1), Tcw.rotation_matrix()(0,2), + Tcw.rotation_matrix()(1,0), Tcw.rotation_matrix()(1,1), Tcw.rotation_matrix()(1,2), + Tcw.rotation_matrix()(2,0), Tcw.rotation_matrix()(2,1), Tcw.rotation_matrix()(2,2) + ), + cv::Affine3d::Vec3( + Tcw.translation()(0,0), Tcw.translation()(1,0), Tcw.translation()(2,0) + ) + ); + cv::imshow("image", color );//显示图片 + //cv::waitKey(1); + cv::waitKey(0); + vis.setWidgetPose( "Camera", M);//显示相机位姿 + vis.spinOnce(1, false); + } + + return 0; +} diff --git a/vSLAM/ch9 project/0.4/.kdev4/0.4.kdev4 b/vSLAM/ch9 project/0.4/.kdev4/0.4.kdev4 new file mode 100644 index 00000000..2caefcc1 --- /dev/null +++ b/vSLAM/ch9 project/0.4/.kdev4/0.4.kdev4 @@ -0,0 +1,39 @@ +[Buildset] +BuildItems=@Variant(\x00\x00\x00\t\x00\x00\x00\x00\x01\x00\x00\x00\x0b\x00\x00\x00\x00\x01\x00\x00\x00\x06\x000\x00.\x004) + +[CMake] +Build Directory Count=1 +Current Build Directory Index=0 +ProjectRootRelative=./ + +[CMake][CMake Build Directory 0] +Build Directory Path=file:///home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9%20project/0.4/build +Build Type=Debug +CMake Binary=file:///usr/bin/cmake +Environment Profile= +Extra Arguments= +Install Directory=file:///usr/local + +[Launch] +Launch Configurations=Launch Configuration 0 + +[Launch][Launch Configuration 0] +Configured Launch Modes=execute +Configured Launchers=nativeAppLauncher +Name=run_vo +Type=Native Application + +[Launch][Launch Configuration 0][Data] +Arguments=../config/default.yaml +Dependencies=@Variant(\x00\x00\x00\t\x00\x00\x00\x00\x01\x00\x00\x00\x0b\x00\x00\x00\x00\x03\x00\x00\x00\x06\x000\x00.\x004\x00\x00\x00\x08\x00t\x00e\x00s\x00t\x00\x00\x00\x0c\x00r\x00u\x00n\x00_\x00v\x00o) +Dependency Action=Nothing +EnvironmentGroup=default +Executable=file:///home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9%20project/0.4/bin/run_vo +External Terminal=konsole --noclose --workdir %workdir -e %exe +Project Target=0.4,test,run_vo +Use External Terminal=false +Working Directory= +isExecutable=true + +[Project] +VersionControlSupport=kdevgit diff --git a/vSLAM/ch9 project/0.4/0.4.kdev4 b/vSLAM/ch9 project/0.4/0.4.kdev4 new file mode 100644 index 00000000..a20c9216 --- /dev/null +++ b/vSLAM/ch9 project/0.4/0.4.kdev4 @@ -0,0 +1,3 @@ +[Project] +Manager=KDevCMakeManager +Name=0.4 diff --git a/vSLAM/ch9 project/0.4/CMakeLists.txt b/vSLAM/ch9 project/0.4/CMakeLists.txt new file mode 100644 index 00000000..2f91c5f9 --- /dev/null +++ b/vSLAM/ch9 project/0.4/CMakeLists.txt @@ -0,0 +1,33 @@ +cmake_minimum_required( VERSION 2.8 ) +project ( myslam ) + +set( CMAKE_CXX_COMPILER "g++" ) +set( CMAKE_BUILD_TYPE "Release" ) +set( CMAKE_CXX_FLAGS "-std=c++11 -march=native -O3" ) + +list( APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules ) +set( EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin ) +set( LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib ) + +############### dependencies ###################### +# Eigen +include_directories( "/usr/include/eigen3" ) +# OpenCV +find_package( OpenCV 3.1 REQUIRED ) +include_directories( ${OpenCV_INCLUDE_DIRS} ) +# Sophus +find_package( Sophus REQUIRED ) +include_directories( ${Sophus_INCLUDE_DIRS} ) +# G2O +find_package( G2O REQUIRED ) +include_directories( ${G2O_INCLUDE_DIRS} ) + +set( THIRD_PARTY_LIBS + ${OpenCV_LIBS} + ${Sophus_LIBRARIES} + g2o_core g2o_stuff g2o_types_sba +) +############### dependencies ###################### +include_directories( ${PROJECT_SOURCE_DIR}/include ) +add_subdirectory( src ) +add_subdirectory( test ) \ No newline at end of file diff --git a/vSLAM/ch9 project/0.4/bin/run_vo b/vSLAM/ch9 project/0.4/bin/run_vo new file mode 100755 index 00000000..f61e53aa Binary files /dev/null and b/vSLAM/ch9 project/0.4/bin/run_vo differ diff --git a/vSLAM/ch9 project/0.4/build/CMakeCache.txt b/vSLAM/ch9 project/0.4/build/CMakeCache.txt new file mode 100644 index 00000000..959f4c2f --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/CMakeCache.txt @@ -0,0 +1,455 @@ +# This is the CMakeCache file. +# For build in directory: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build +# It was generated by CMake: /usr/bin/cmake +# You can edit this file to change values found and used by cmake. +# If you do not want to change any of the values, simply exit the editor. +# If you do want to change a value, simply edit, save, and exit the editor. +# The syntax for the file is as follows: +# KEY:TYPE=VALUE +# KEY is the name of a variable in the cache. +# TYPE is a hint to GUIs for the type of VALUE, DO NOT EDIT TYPE!. +# VALUE is the current value for the KEY. + +######################## +# EXTERNAL cache entries +######################## + +//Path to a program. +CMAKE_AR:FILEPATH=/usr/bin/ar + +//Choose the type of build, options are: None(CMAKE_CXX_FLAGS or +// CMAKE_C_FLAGS used) Debug Release RelWithDebInfo MinSizeRel. +CMAKE_BUILD_TYPE:STRING=Debug + +//Enable/Disable color output during build. +CMAKE_COLOR_MAKEFILE:BOOL=ON + +//CXX compiler. +CMAKE_CXX_COMPILER:FILEPATH=/usr/bin/c++ + +//Flags used by the compiler during all build types. +CMAKE_CXX_FLAGS:STRING= + +//Flags used by the compiler during debug builds. +CMAKE_CXX_FLAGS_DEBUG:STRING=-g + +//Flags used by the compiler during release minsize builds. +CMAKE_CXX_FLAGS_MINSIZEREL:STRING=-Os -DNDEBUG + +//Flags used by the compiler during release builds (/MD /Ob1 /Oi +// /Ot /Oy /Gs will produce slightly less optimized but smaller +// files). +CMAKE_CXX_FLAGS_RELEASE:STRING=-O3 -DNDEBUG + +//Flags used by the compiler during Release with Debug Info builds. +CMAKE_CXX_FLAGS_RELWITHDEBINFO:STRING=-O2 -g -DNDEBUG + +//C compiler. +CMAKE_C_COMPILER:FILEPATH=/usr/bin/cc + +//Flags used by the compiler during all build types. +CMAKE_C_FLAGS:STRING= + +//Flags used by the compiler during debug builds. +CMAKE_C_FLAGS_DEBUG:STRING=-g + +//Flags used by the compiler during release minsize builds. +CMAKE_C_FLAGS_MINSIZEREL:STRING=-Os -DNDEBUG + +//Flags used by the compiler during release builds (/MD /Ob1 /Oi +// /Ot /Oy /Gs will produce slightly less optimized but smaller +// files). +CMAKE_C_FLAGS_RELEASE:STRING=-O3 -DNDEBUG + +//Flags used by the compiler during Release with Debug Info builds. +CMAKE_C_FLAGS_RELWITHDEBINFO:STRING=-O2 -g -DNDEBUG + +//Flags used by the linker. +CMAKE_EXE_LINKER_FLAGS:STRING=' ' + +//Flags used by the linker during debug builds. +CMAKE_EXE_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during release minsize builds. +CMAKE_EXE_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during release builds. +CMAKE_EXE_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during Release with Debug Info builds. +CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//Enable/Disable output of compile commands during generation. +CMAKE_EXPORT_COMPILE_COMMANDS:BOOL=OFF + +//Install path prefix, prepended onto install directories. +CMAKE_INSTALL_PREFIX:PATH=/usr/local + +//Path to a program. +CMAKE_LINKER:FILEPATH=/usr/bin/ld + +//Path to a program. +CMAKE_MAKE_PROGRAM:FILEPATH=/usr/bin/make + +//Flags used by the linker during the creation of modules. +CMAKE_MODULE_LINKER_FLAGS:STRING=' ' + +//Flags used by the linker during debug builds. +CMAKE_MODULE_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during release minsize builds. +CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during release builds. +CMAKE_MODULE_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during Release with Debug Info builds. +CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//Path to a program. +CMAKE_NM:FILEPATH=/usr/bin/nm + +//Path to a program. +CMAKE_OBJCOPY:FILEPATH=/usr/bin/objcopy + +//Path to a program. +CMAKE_OBJDUMP:FILEPATH=/usr/bin/objdump + +//Value Computed by CMake +CMAKE_PROJECT_NAME:STATIC=myslam + +//Path to a program. +CMAKE_RANLIB:FILEPATH=/usr/bin/ranlib + +//Flags used by the linker during the creation of dll's. +CMAKE_SHARED_LINKER_FLAGS:STRING=' ' + +//Flags used by the linker during debug builds. +CMAKE_SHARED_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during release minsize builds. +CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during release builds. +CMAKE_SHARED_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during Release with Debug Info builds. +CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//If set, runtime paths are not added when installing shared libraries, +// but are added when building. +CMAKE_SKIP_INSTALL_RPATH:BOOL=NO + +//If set, runtime paths are not added when using shared libraries. +CMAKE_SKIP_RPATH:BOOL=NO + +//Flags used by the linker during the creation of static libraries. +CMAKE_STATIC_LINKER_FLAGS:STRING= + +//Flags used by the linker during debug builds. +CMAKE_STATIC_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during release minsize builds. +CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during release builds. +CMAKE_STATIC_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during Release with Debug Info builds. +CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//Path to a program. +CMAKE_STRIP:FILEPATH=/usr/bin/strip + +//If true, cmake will use relative paths in makefiles and projects. +CMAKE_USE_RELATIVE_PATHS:BOOL=OFF + +//If this value is on, makefiles will be generated without the +// .SILENT directive, and all commands will be echoed to the console +// during the make. This is useful for debugging only. With Visual +// Studio IDE projects all commands are done without /nologo. +CMAKE_VERBOSE_MAKEFILE:BOOL=FALSE + +//Path to a library. +G2O_CLI_LIBRARY:FILEPATH=/usr/local/lib/libg2o_cli.so + +//Path to a library. +G2O_CLI_LIBRARY_DEBUG:FILEPATH=G2O_CLI_LIBRARY_DEBUG-NOTFOUND + +//Path to a library. +G2O_CORE_LIBRARY:FILEPATH=/usr/local/lib/libg2o_core.so + +//Path to a library. +G2O_CORE_LIBRARY_DEBUG:FILEPATH=G2O_CORE_LIBRARY_DEBUG-NOTFOUND + +//Path to a file. +G2O_INCLUDE_DIR:PATH=/usr/local/include + +//Path to a library. +G2O_SOLVER_CHOLMOD:FILEPATH=/usr/local/lib/libg2o_solver_cholmod.so + +//Path to a library. +G2O_SOLVER_CHOLMOD_DEBUG:FILEPATH=G2O_SOLVER_CHOLMOD_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_CSPARSE:FILEPATH=/usr/local/lib/libg2o_solver_csparse.so + +//Path to a library. +G2O_SOLVER_CSPARSE_DEBUG:FILEPATH=G2O_SOLVER_CSPARSE_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_CSPARSE_EXTENSION:FILEPATH=/usr/local/lib/libg2o_csparse_extension.so + +//Path to a library. +G2O_SOLVER_CSPARSE_EXTENSION_DEBUG:FILEPATH=G2O_SOLVER_CSPARSE_EXTENSION_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_DENSE:FILEPATH=/usr/local/lib/libg2o_solver_dense.so + +//Path to a library. +G2O_SOLVER_DENSE_DEBUG:FILEPATH=G2O_SOLVER_DENSE_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_EIGEN:FILEPATH=/usr/local/lib/libg2o_solver_eigen.so + +//Path to a library. +G2O_SOLVER_EIGEN_DEBUG:FILEPATH=G2O_SOLVER_EIGEN_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_PCG:FILEPATH=/usr/local/lib/libg2o_solver_pcg.so + +//Path to a library. +G2O_SOLVER_PCG_DEBUG:FILEPATH=G2O_SOLVER_PCG_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_SLAM2D_LINEAR:FILEPATH=/usr/local/lib/libg2o_solver_slam2d_linear.so + +//Path to a library. +G2O_SOLVER_SLAM2D_LINEAR_DEBUG:FILEPATH=G2O_SOLVER_SLAM2D_LINEAR_DEBUG-NOTFOUND + +//Path to a library. +G2O_SOLVER_STRUCTURE_ONLY:FILEPATH=/usr/local/lib/libg2o_solver_structure_only.so + +//Path to a library. +G2O_SOLVER_STRUCTURE_ONLY_DEBUG:FILEPATH=G2O_SOLVER_STRUCTURE_ONLY_DEBUG-NOTFOUND + +//Path to a library. +G2O_STUFF_LIBRARY:FILEPATH=/usr/local/lib/libg2o_stuff.so + +//Path to a library. +G2O_STUFF_LIBRARY_DEBUG:FILEPATH=G2O_STUFF_LIBRARY_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_DATA:FILEPATH=/usr/local/lib/libg2o_types_data.so + +//Path to a library. +G2O_TYPES_DATA_DEBUG:FILEPATH=G2O_TYPES_DATA_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_ICP:FILEPATH=/usr/local/lib/libg2o_types_icp.so + +//Path to a library. +G2O_TYPES_ICP_DEBUG:FILEPATH=G2O_TYPES_ICP_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_SBA:FILEPATH=/usr/local/lib/libg2o_types_sba.so + +//Path to a library. +G2O_TYPES_SBA_DEBUG:FILEPATH=G2O_TYPES_SBA_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_SCLAM2D:FILEPATH=/usr/local/lib/libg2o_types_sclam2d.so + +//Path to a library. +G2O_TYPES_SCLAM2D_DEBUG:FILEPATH=G2O_TYPES_SCLAM2D_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_SIM3:FILEPATH=/usr/local/lib/libg2o_types_sim3.so + +//Path to a library. +G2O_TYPES_SIM3_DEBUG:FILEPATH=G2O_TYPES_SIM3_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_SLAM2D:FILEPATH=/usr/local/lib/libg2o_types_slam2d.so + +//Path to a library. +G2O_TYPES_SLAM2D_DEBUG:FILEPATH=G2O_TYPES_SLAM2D_DEBUG-NOTFOUND + +//Path to a library. +G2O_TYPES_SLAM3D:FILEPATH=/usr/local/lib/libg2o_types_slam3d.so + +//Path to a library. +G2O_TYPES_SLAM3D_DEBUG:FILEPATH=G2O_TYPES_SLAM3D_DEBUG-NOTFOUND + +//Path where debug 3rdparty OpenCV dependencies are located +OpenCV_3RDPARTY_LIB_DIR_DBG:PATH=/usr/local/share/OpenCV/3rdparty/lib + +//Path where release 3rdparty OpenCV dependencies are located +OpenCV_3RDPARTY_LIB_DIR_OPT:PATH=/usr/local/share/OpenCV/3rdparty/lib + +OpenCV_CONFIG_PATH:FILEPATH=/usr/local/share/OpenCV + +//The directory containing a CMake configuration file for OpenCV. +OpenCV_DIR:PATH=/usr/local/share/OpenCV + +//Path where debug OpenCV libraries are located +OpenCV_LIB_DIR_DBG:PATH= + +//Path where release OpenCV libraries are located +OpenCV_LIB_DIR_OPT:PATH= + +//The directory containing a CMake configuration file for Sophus. +Sophus_DIR:PATH=/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build + +//Value Computed by CMake +myslam_BINARY_DIR:STATIC=/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build + +//Dependencies for the target +myslam_LIB_DEPENDS:STATIC=general;opencv_viz;general;opencv_videostab;general;opencv_videoio;general;opencv_video;general;opencv_superres;general;opencv_stitching;general;opencv_shape;general;opencv_photo;general;opencv_objdetect;general;opencv_ml;general;opencv_imgproc;general;opencv_imgcodecs;general;opencv_highgui;general;opencv_flann;general;opencv_features2d;general;opencv_core;general;opencv_calib3d;general;/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build/libSophus.so;general;g2o_core;general;g2o_stuff;general;g2o_types_sba; + +//Value Computed by CMake +myslam_SOURCE_DIR:STATIC=/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4 + + +######################## +# INTERNAL cache entries +######################## + +//ADVANCED property for variable: CMAKE_AR +CMAKE_AR-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_BUILD_TOOL +CMAKE_BUILD_TOOL-ADVANCED:INTERNAL=1 +//What is the target build tool cmake is generating for. +CMAKE_BUILD_TOOL:INTERNAL=/usr/bin/make +//This is the directory where this CMakeCache.txt was created +CMAKE_CACHEFILE_DIR:INTERNAL=/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build +//Major version of cmake used to create the current loaded cache +CMAKE_CACHE_MAJOR_VERSION:INTERNAL=2 +//Minor version of cmake used to create the current loaded cache +CMAKE_CACHE_MINOR_VERSION:INTERNAL=8 +//Patch version of cmake used to create the current loaded cache +CMAKE_CACHE_PATCH_VERSION:INTERNAL=12 +//ADVANCED property for variable: CMAKE_COLOR_MAKEFILE +CMAKE_COLOR_MAKEFILE-ADVANCED:INTERNAL=1 +//Path to CMake executable. +CMAKE_COMMAND:INTERNAL=/usr/bin/cmake +//Path to cpack program executable. +CMAKE_CPACK_COMMAND:INTERNAL=/usr/bin/cpack +//Path to ctest program executable. +CMAKE_CTEST_COMMAND:INTERNAL=/usr/bin/ctest +//ADVANCED property for variable: CMAKE_CXX_COMPILER +CMAKE_CXX_COMPILER-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS +CMAKE_CXX_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_DEBUG +CMAKE_CXX_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_MINSIZEREL +CMAKE_CXX_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_RELEASE +CMAKE_CXX_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_RELWITHDEBINFO +CMAKE_CXX_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_COMPILER +CMAKE_C_COMPILER-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS +CMAKE_C_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS_DEBUG +CMAKE_C_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS_MINSIZEREL +CMAKE_C_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS_RELEASE +CMAKE_C_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS_RELWITHDEBINFO +CMAKE_C_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//Executable file format +CMAKE_EXECUTABLE_FORMAT:INTERNAL=ELF +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS +CMAKE_EXE_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_DEBUG +CMAKE_EXE_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_MINSIZEREL +CMAKE_EXE_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_RELEASE +CMAKE_EXE_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXPORT_COMPILE_COMMANDS +CMAKE_EXPORT_COMPILE_COMMANDS-ADVANCED:INTERNAL=1 +//Name of generator. +CMAKE_GENERATOR:INTERNAL=Unix Makefiles +//Name of generator toolset. +CMAKE_GENERATOR_TOOLSET:INTERNAL= +//Start directory with the top level CMakeLists.txt file for this +// project +CMAKE_HOME_DIRECTORY:INTERNAL=/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4 +//Install .so files without execute permission. +CMAKE_INSTALL_SO_NO_EXE:INTERNAL=1 +//ADVANCED property for variable: CMAKE_LINKER +CMAKE_LINKER-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MAKE_PROGRAM +CMAKE_MAKE_PROGRAM-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS +CMAKE_MODULE_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_DEBUG +CMAKE_MODULE_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL +CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_RELEASE +CMAKE_MODULE_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_NM +CMAKE_NM-ADVANCED:INTERNAL=1 +//number of local generators +CMAKE_NUMBER_OF_LOCAL_GENERATORS:INTERNAL=3 +//ADVANCED property for variable: CMAKE_OBJCOPY +CMAKE_OBJCOPY-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_OBJDUMP +CMAKE_OBJDUMP-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_RANLIB +CMAKE_RANLIB-ADVANCED:INTERNAL=1 +//Path to CMake installation. +CMAKE_ROOT:INTERNAL=/usr/share/cmake-2.8 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS +CMAKE_SHARED_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_DEBUG +CMAKE_SHARED_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL +CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_RELEASE +CMAKE_SHARED_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SKIP_INSTALL_RPATH +CMAKE_SKIP_INSTALL_RPATH-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SKIP_RPATH +CMAKE_SKIP_RPATH-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS +CMAKE_STATIC_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_DEBUG +CMAKE_STATIC_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL +CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_RELEASE +CMAKE_STATIC_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STRIP +CMAKE_STRIP-ADVANCED:INTERNAL=1 +//uname command +CMAKE_UNAME:INTERNAL=/bin/uname +//ADVANCED property for variable: CMAKE_USE_RELATIVE_PATHS +CMAKE_USE_RELATIVE_PATHS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_VERBOSE_MAKEFILE +CMAKE_VERBOSE_MAKEFILE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: OpenCV_3RDPARTY_LIB_DIR_DBG +OpenCV_3RDPARTY_LIB_DIR_DBG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: OpenCV_3RDPARTY_LIB_DIR_OPT +OpenCV_3RDPARTY_LIB_DIR_OPT-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: OpenCV_CONFIG_PATH +OpenCV_CONFIG_PATH-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: OpenCV_LIB_DIR_DBG +OpenCV_LIB_DIR_DBG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: OpenCV_LIB_DIR_OPT +OpenCV_LIB_DIR_OPT-ADVANCED:INTERNAL=1 + diff --git a/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CMakeCCompiler.cmake b/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CMakeCCompiler.cmake new file mode 100644 index 00000000..f4a508be --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CMakeCCompiler.cmake @@ -0,0 +1,56 @@ +set(CMAKE_C_COMPILER "/usr/bin/cc") +set(CMAKE_C_COMPILER_ARG1 "") +set(CMAKE_C_COMPILER_ID "GNU") +set(CMAKE_C_COMPILER_VERSION "4.8.4") +set(CMAKE_C_PLATFORM_ID "Linux") + +set(CMAKE_AR "/usr/bin/ar") +set(CMAKE_RANLIB "/usr/bin/ranlib") +set(CMAKE_LINKER "/usr/bin/ld") +set(CMAKE_COMPILER_IS_GNUCC 1) +set(CMAKE_C_COMPILER_LOADED 1) +set(CMAKE_C_COMPILER_WORKS TRUE) +set(CMAKE_C_ABI_COMPILED TRUE) +set(CMAKE_COMPILER_IS_MINGW ) +set(CMAKE_COMPILER_IS_CYGWIN ) +if(CMAKE_COMPILER_IS_CYGWIN) + set(CYGWIN 1) + set(UNIX 1) +endif() + +set(CMAKE_C_COMPILER_ENV_VAR "CC") + +if(CMAKE_COMPILER_IS_MINGW) + set(MINGW 1) +endif() +set(CMAKE_C_COMPILER_ID_RUN 1) +set(CMAKE_C_SOURCE_FILE_EXTENSIONS c) +set(CMAKE_C_IGNORE_EXTENSIONS h;H;o;O;obj;OBJ;def;DEF;rc;RC) +set(CMAKE_C_LINKER_PREFERENCE 10) + +# Save compiler ABI information. +set(CMAKE_C_SIZEOF_DATA_PTR "8") +set(CMAKE_C_COMPILER_ABI "ELF") +set(CMAKE_C_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") + +if(CMAKE_C_SIZEOF_DATA_PTR) + set(CMAKE_SIZEOF_VOID_P "${CMAKE_C_SIZEOF_DATA_PTR}") +endif() + +if(CMAKE_C_COMPILER_ABI) + set(CMAKE_INTERNAL_PLATFORM_ABI "${CMAKE_C_COMPILER_ABI}") +endif() + +if(CMAKE_C_LIBRARY_ARCHITECTURE) + set(CMAKE_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") +endif() + + + + +set(CMAKE_C_IMPLICIT_LINK_LIBRARIES "c") +set(CMAKE_C_IMPLICIT_LINK_DIRECTORIES "/usr/lib/gcc/x86_64-linux-gnu/4.8;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib") +set(CMAKE_C_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES "") + + + diff --git a/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake b/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake new file mode 100644 index 00000000..1ca40dbc --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake @@ -0,0 +1,57 @@ +set(CMAKE_CXX_COMPILER "/usr/bin/c++") +set(CMAKE_CXX_COMPILER_ARG1 "") +set(CMAKE_CXX_COMPILER_ID "GNU") +set(CMAKE_CXX_COMPILER_VERSION "4.8.4") +set(CMAKE_CXX_PLATFORM_ID "Linux") + +set(CMAKE_AR "/usr/bin/ar") +set(CMAKE_RANLIB "/usr/bin/ranlib") +set(CMAKE_LINKER "/usr/bin/ld") +set(CMAKE_COMPILER_IS_GNUCXX 1) +set(CMAKE_CXX_COMPILER_LOADED 1) +set(CMAKE_CXX_COMPILER_WORKS TRUE) +set(CMAKE_CXX_ABI_COMPILED TRUE) +set(CMAKE_COMPILER_IS_MINGW ) +set(CMAKE_COMPILER_IS_CYGWIN ) +if(CMAKE_COMPILER_IS_CYGWIN) + set(CYGWIN 1) + set(UNIX 1) +endif() + +set(CMAKE_CXX_COMPILER_ENV_VAR "CXX") + +if(CMAKE_COMPILER_IS_MINGW) + set(MINGW 1) +endif() +set(CMAKE_CXX_COMPILER_ID_RUN 1) +set(CMAKE_CXX_IGNORE_EXTENSIONS inl;h;hpp;HPP;H;o;O;obj;OBJ;def;DEF;rc;RC) +set(CMAKE_CXX_SOURCE_FILE_EXTENSIONS C;M;c++;cc;cpp;cxx;m;mm;CPP) +set(CMAKE_CXX_LINKER_PREFERENCE 30) +set(CMAKE_CXX_LINKER_PREFERENCE_PROPAGATES 1) + +# Save compiler ABI information. +set(CMAKE_CXX_SIZEOF_DATA_PTR "8") +set(CMAKE_CXX_COMPILER_ABI "ELF") +set(CMAKE_CXX_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") + +if(CMAKE_CXX_SIZEOF_DATA_PTR) + set(CMAKE_SIZEOF_VOID_P "${CMAKE_CXX_SIZEOF_DATA_PTR}") +endif() + +if(CMAKE_CXX_COMPILER_ABI) + set(CMAKE_INTERNAL_PLATFORM_ABI "${CMAKE_CXX_COMPILER_ABI}") +endif() + +if(CMAKE_CXX_LIBRARY_ARCHITECTURE) + set(CMAKE_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") +endif() + + + + +set(CMAKE_CXX_IMPLICIT_LINK_LIBRARIES "stdc++;m;c") +set(CMAKE_CXX_IMPLICIT_LINK_DIRECTORIES "/usr/lib/gcc/x86_64-linux-gnu/4.8;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib") +set(CMAKE_CXX_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES "") + + + diff --git a/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_C.bin b/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_C.bin new file mode 100755 index 00000000..f909aaac Binary files /dev/null and b/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_C.bin differ diff --git a/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_CXX.bin b/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_CXX.bin new file mode 100755 index 00000000..d6b41c89 Binary files /dev/null and b/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CMakeDetermineCompilerABI_CXX.bin differ diff --git a/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CMakeSystem.cmake b/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CMakeSystem.cmake new file mode 100644 index 00000000..8444407c --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CMakeSystem.cmake @@ -0,0 +1,15 @@ +set(CMAKE_HOST_SYSTEM "Linux-4.4.0-94-generic") +set(CMAKE_HOST_SYSTEM_NAME "Linux") +set(CMAKE_HOST_SYSTEM_VERSION "4.4.0-94-generic") +set(CMAKE_HOST_SYSTEM_PROCESSOR "x86_64") + + + +set(CMAKE_SYSTEM "Linux-4.4.0-94-generic") +set(CMAKE_SYSTEM_NAME "Linux") +set(CMAKE_SYSTEM_VERSION "4.4.0-94-generic") +set(CMAKE_SYSTEM_PROCESSOR "x86_64") + +set(CMAKE_CROSSCOMPILING "FALSE") + +set(CMAKE_SYSTEM_LOADED 1) diff --git a/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CompilerIdC/CMakeCCompilerId.c b/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CompilerIdC/CMakeCCompilerId.c new file mode 100644 index 00000000..cba81d4a --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CompilerIdC/CMakeCCompilerId.c @@ -0,0 +1,389 @@ +#ifdef __cplusplus +# error "A C++ compiler has been selected for C." +#endif + +/* Version number components: V=Version, R=Revision, P=Patch + Version date components: YYYY=Year, MM=Month, DD=Day */ + +#if defined(__18CXX) +# define ID_VOID_MAIN +#endif + +#if defined(__INTEL_COMPILER) || defined(__ICC) +# define COMPILER_ID "Intel" + /* __INTEL_COMPILER = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER/100) +# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER % 10) +# if defined(__INTEL_COMPILER_BUILD_DATE) + /* __INTEL_COMPILER_BUILD_DATE = YYYYMMDD */ +# define COMPILER_VERSION_TWEAK DEC(__INTEL_COMPILER_BUILD_DATE) +# endif + +#elif defined(__PATHCC__) +# define COMPILER_ID "PathScale" +# define COMPILER_VERSION_MAJOR DEC(__PATHCC__) +# define COMPILER_VERSION_MINOR DEC(__PATHCC_MINOR__) +# if defined(__PATHCC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__PATHCC_PATCHLEVEL__) +# endif + +#elif defined(__clang__) +# define COMPILER_ID "Clang" +# define COMPILER_VERSION_MAJOR DEC(__clang_major__) +# define COMPILER_VERSION_MINOR DEC(__clang_minor__) +# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__) + +#elif defined(__BORLANDC__) && defined(__CODEGEARC_VERSION__) +# define COMPILER_ID "Embarcadero" +# define COMPILER_VERSION_MAJOR HEX(__CODEGEARC_VERSION__>>24 & 0x00FF) +# define COMPILER_VERSION_MINOR HEX(__CODEGEARC_VERSION__>>16 & 0x00FF) +# define COMPILER_VERSION_PATCH HEX(__CODEGEARC_VERSION__ & 0xFFFF) + +#elif defined(__BORLANDC__) +# define COMPILER_ID "Borland" + /* __BORLANDC__ = 0xVRR */ +# define COMPILER_VERSION_MAJOR HEX(__BORLANDC__>>8) +# define COMPILER_VERSION_MINOR HEX(__BORLANDC__ & 0xFF) + +#elif defined(__WATCOMC__) +# define COMPILER_ID "Watcom" + /* __WATCOMC__ = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(__WATCOMC__ / 100) +# define COMPILER_VERSION_MINOR DEC(__WATCOMC__ % 100) + +#elif defined(__SUNPRO_C) +# define COMPILER_ID "SunPro" +# if __SUNPRO_C >= 0x5100 + /* __SUNPRO_C = 0xVRRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_C>>12) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_C>>4 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_C & 0xF) +# else + /* __SUNPRO_C = 0xVRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_C>>8) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_C>>4 & 0xF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_C & 0xF) +# endif + +#elif defined(__HP_cc) +# define COMPILER_ID "HP" + /* __HP_cc = VVRRPP */ +# define COMPILER_VERSION_MAJOR DEC(__HP_cc/10000) +# define COMPILER_VERSION_MINOR DEC(__HP_cc/100 % 100) +# define COMPILER_VERSION_PATCH DEC(__HP_cc % 100) + +#elif defined(__DECC) +# define COMPILER_ID "Compaq" + /* __DECC_VER = VVRRTPPPP */ +# define COMPILER_VERSION_MAJOR DEC(__DECC_VER/10000000) +# define COMPILER_VERSION_MINOR DEC(__DECC_VER/100000 % 100) +# define COMPILER_VERSION_PATCH DEC(__DECC_VER % 10000) + +#elif defined(__IBMC__) +# if defined(__COMPILER_VER__) +# define COMPILER_ID "zOS" +# else +# if __IBMC__ >= 800 +# define COMPILER_ID "XL" +# else +# define COMPILER_ID "VisualAge" +# endif + /* __IBMC__ = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__IBMC__/100) +# define COMPILER_VERSION_MINOR DEC(__IBMC__/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__IBMC__ % 10) +# endif + +#elif defined(__PGI) +# define COMPILER_ID "PGI" +# define COMPILER_VERSION_MAJOR DEC(__PGIC__) +# define COMPILER_VERSION_MINOR DEC(__PGIC_MINOR__) +# if defined(__PGIC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__PGIC_PATCHLEVEL__) +# endif + +#elif defined(_CRAYC) +# define COMPILER_ID "Cray" +# define COMPILER_VERSION_MAJOR DEC(_RELEASE) +# define COMPILER_VERSION_MINOR DEC(_RELEASE_MINOR) + +#elif defined(__TI_COMPILER_VERSION__) +# define COMPILER_ID "TI" + /* __TI_COMPILER_VERSION__ = VVVRRRPPP */ +# define COMPILER_VERSION_MAJOR DEC(__TI_COMPILER_VERSION__/1000000) +# define COMPILER_VERSION_MINOR DEC(__TI_COMPILER_VERSION__/1000 % 1000) +# define COMPILER_VERSION_PATCH DEC(__TI_COMPILER_VERSION__ % 1000) + +#elif defined(__TINYC__) +# define COMPILER_ID "TinyCC" + +#elif defined(__SCO_VERSION__) +# define COMPILER_ID "SCO" + +#elif defined(__GNUC__) +# define COMPILER_ID "GNU" +# define COMPILER_VERSION_MAJOR DEC(__GNUC__) +# define COMPILER_VERSION_MINOR DEC(__GNUC_MINOR__) +# if defined(__GNUC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__) +# endif + +#elif defined(_MSC_VER) +# define COMPILER_ID "MSVC" + /* _MSC_VER = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(_MSC_VER / 100) +# define COMPILER_VERSION_MINOR DEC(_MSC_VER % 100) +# if defined(_MSC_FULL_VER) +# if _MSC_VER >= 1400 + /* _MSC_FULL_VER = VVRRPPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 100000) +# else + /* _MSC_FULL_VER = VVRRPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 10000) +# endif +# endif +# if defined(_MSC_BUILD) +# define COMPILER_VERSION_TWEAK DEC(_MSC_BUILD) +# endif + +/* Analog VisualDSP++ >= 4.5.6 */ +#elif defined(__VISUALDSPVERSION__) +# define COMPILER_ID "ADSP" + /* __VISUALDSPVERSION__ = 0xVVRRPP00 */ +# define COMPILER_VERSION_MAJOR HEX(__VISUALDSPVERSION__>>24) +# define COMPILER_VERSION_MINOR HEX(__VISUALDSPVERSION__>>16 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__VISUALDSPVERSION__>>8 & 0xFF) + +/* Analog VisualDSP++ < 4.5.6 */ +#elif defined(__ADSPBLACKFIN__) || defined(__ADSPTS__) || defined(__ADSP21000__) +# define COMPILER_ID "ADSP" + +/* IAR Systems compiler for embedded systems. + http://www.iar.com */ +#elif defined(__IAR_SYSTEMS_ICC__ ) || defined(__IAR_SYSTEMS_ICC) +# define COMPILER_ID "IAR" + +/* sdcc, the small devices C compiler for embedded systems, + http://sdcc.sourceforge.net */ +#elif defined(SDCC) +# define COMPILER_ID "SDCC" + /* SDCC = VRP */ +# define COMPILER_VERSION_MAJOR DEC(SDCC/100) +# define COMPILER_VERSION_MINOR DEC(SDCC/10 % 10) +# define COMPILER_VERSION_PATCH DEC(SDCC % 10) + +#elif defined(_SGI_COMPILER_VERSION) || defined(_COMPILER_VERSION) +# define COMPILER_ID "MIPSpro" +# if defined(_SGI_COMPILER_VERSION) + /* _SGI_COMPILER_VERSION = VRP */ +# define COMPILER_VERSION_MAJOR DEC(_SGI_COMPILER_VERSION/100) +# define COMPILER_VERSION_MINOR DEC(_SGI_COMPILER_VERSION/10 % 10) +# define COMPILER_VERSION_PATCH DEC(_SGI_COMPILER_VERSION % 10) +# else + /* _COMPILER_VERSION = VRP */ +# define COMPILER_VERSION_MAJOR DEC(_COMPILER_VERSION/100) +# define COMPILER_VERSION_MINOR DEC(_COMPILER_VERSION/10 % 10) +# define COMPILER_VERSION_PATCH DEC(_COMPILER_VERSION % 10) +# endif + +/* This compiler is either not known or is too old to define an + identification macro. Try to identify the platform and guess that + it is the native compiler. */ +#elif defined(__sgi) +# define COMPILER_ID "MIPSpro" + +#elif defined(__hpux) || defined(__hpua) +# define COMPILER_ID "HP" + +#else /* unknown compiler */ +# define COMPILER_ID "" + +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_compiler = "INFO" ":" "compiler[" COMPILER_ID "]"; + +/* Identify known platforms by name. */ +#if defined(__linux) || defined(__linux__) || defined(linux) +# define PLATFORM_ID "Linux" + +#elif defined(__CYGWIN__) +# define PLATFORM_ID "Cygwin" + +#elif defined(__MINGW32__) +# define PLATFORM_ID "MinGW" + +#elif defined(__APPLE__) +# define PLATFORM_ID "Darwin" + +#elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32) +# define PLATFORM_ID "Windows" + +#elif defined(__FreeBSD__) || defined(__FreeBSD) +# define PLATFORM_ID "FreeBSD" + +#elif defined(__NetBSD__) || defined(__NetBSD) +# define PLATFORM_ID "NetBSD" + +#elif defined(__OpenBSD__) || defined(__OPENBSD) +# define PLATFORM_ID "OpenBSD" + +#elif defined(__sun) || defined(sun) +# define PLATFORM_ID "SunOS" + +#elif defined(_AIX) || defined(__AIX) || defined(__AIX__) || defined(__aix) || defined(__aix__) +# define PLATFORM_ID "AIX" + +#elif defined(__sgi) || defined(__sgi__) || defined(_SGI) +# define PLATFORM_ID "IRIX" + +#elif defined(__hpux) || defined(__hpux__) +# define PLATFORM_ID "HP-UX" + +#elif defined(__HAIKU__) +# define PLATFORM_ID "Haiku" + +#elif defined(__BeOS) || defined(__BEOS__) || defined(_BEOS) +# define PLATFORM_ID "BeOS" + +#elif defined(__QNX__) || defined(__QNXNTO__) +# define PLATFORM_ID "QNX" + +#elif defined(__tru64) || defined(_tru64) || defined(__TRU64__) +# define PLATFORM_ID "Tru64" + +#elif defined(__riscos) || defined(__riscos__) +# define PLATFORM_ID "RISCos" + +#elif defined(__sinix) || defined(__sinix__) || defined(__SINIX__) +# define PLATFORM_ID "SINIX" + +#elif defined(__UNIX_SV__) +# define PLATFORM_ID "UNIX_SV" + +#elif defined(__bsdos__) +# define PLATFORM_ID "BSDOS" + +#elif defined(_MPRAS) || defined(MPRAS) +# define PLATFORM_ID "MP-RAS" + +#elif defined(__osf) || defined(__osf__) +# define PLATFORM_ID "OSF1" + +#elif defined(_SCO_SV) || defined(SCO_SV) || defined(sco_sv) +# define PLATFORM_ID "SCO_SV" + +#elif defined(__ultrix) || defined(__ultrix__) || defined(_ULTRIX) +# define PLATFORM_ID "ULTRIX" + +#elif defined(__XENIX__) || defined(_XENIX) || defined(XENIX) +# define PLATFORM_ID "Xenix" + +#else /* unknown platform */ +# define PLATFORM_ID "" + +#endif + +/* For windows compilers MSVC and Intel we can determine + the architecture of the compiler being used. This is because + the compilers do not have flags that can change the architecture, + but rather depend on which compiler is being used +*/ +#if defined(_WIN32) && defined(_MSC_VER) +# if defined(_M_IA64) +# define ARCHITECTURE_ID "IA64" + +# elif defined(_M_X64) || defined(_M_AMD64) +# define ARCHITECTURE_ID "x64" + +# elif defined(_M_IX86) +# define ARCHITECTURE_ID "X86" + +# elif defined(_M_ARM) +# define ARCHITECTURE_ID "ARM" + +# elif defined(_M_MIPS) +# define ARCHITECTURE_ID "MIPS" + +# elif defined(_M_SH) +# define ARCHITECTURE_ID "SHx" + +# else /* unknown architecture */ +# define ARCHITECTURE_ID "" +# endif + +#else +# define ARCHITECTURE_ID "" +#endif + +/* Convert integer to decimal digit literals. */ +#define DEC(n) \ + ('0' + (((n) / 10000000)%10)), \ + ('0' + (((n) / 1000000)%10)), \ + ('0' + (((n) / 100000)%10)), \ + ('0' + (((n) / 10000)%10)), \ + ('0' + (((n) / 1000)%10)), \ + ('0' + (((n) / 100)%10)), \ + ('0' + (((n) / 10)%10)), \ + ('0' + ((n) % 10)) + +/* Convert integer to hex digit literals. */ +#define HEX(n) \ + ('0' + ((n)>>28 & 0xF)), \ + ('0' + ((n)>>24 & 0xF)), \ + ('0' + ((n)>>20 & 0xF)), \ + ('0' + ((n)>>16 & 0xF)), \ + ('0' + ((n)>>12 & 0xF)), \ + ('0' + ((n)>>8 & 0xF)), \ + ('0' + ((n)>>4 & 0xF)), \ + ('0' + ((n) & 0xF)) + +/* Construct a string literal encoding the version number components. */ +#ifdef COMPILER_VERSION_MAJOR +char const info_version[] = { + 'I', 'N', 'F', 'O', ':', + 'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','[', + COMPILER_VERSION_MAJOR, +# ifdef COMPILER_VERSION_MINOR + '.', COMPILER_VERSION_MINOR, +# ifdef COMPILER_VERSION_PATCH + '.', COMPILER_VERSION_PATCH, +# ifdef COMPILER_VERSION_TWEAK + '.', COMPILER_VERSION_TWEAK, +# endif +# endif +# endif + ']','\0'}; +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_platform = "INFO" ":" "platform[" PLATFORM_ID "]"; +char const* info_arch = "INFO" ":" "arch[" ARCHITECTURE_ID "]"; + + + +/*--------------------------------------------------------------------------*/ + +#ifdef ID_VOID_MAIN +void main() {} +#else +int main(int argc, char* argv[]) +{ + int require = 0; + require += info_compiler[argc]; + require += info_platform[argc]; + require += info_arch[argc]; +#ifdef COMPILER_VERSION_MAJOR + require += info_version[argc]; +#endif + (void)argv; + return require; +} +#endif diff --git a/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CompilerIdC/a.out b/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CompilerIdC/a.out new file mode 100755 index 00000000..49a5ca2e Binary files /dev/null and b/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CompilerIdC/a.out differ diff --git a/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CompilerIdCXX/CMakeCXXCompilerId.cpp b/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CompilerIdCXX/CMakeCXXCompilerId.cpp new file mode 100644 index 00000000..e8220b26 --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CompilerIdCXX/CMakeCXXCompilerId.cpp @@ -0,0 +1,377 @@ +/* This source file must have a .cpp extension so that all C++ compilers + recognize the extension without flags. Borland does not know .cxx for + example. */ +#ifndef __cplusplus +# error "A C compiler has been selected for C++." +#endif + +/* Version number components: V=Version, R=Revision, P=Patch + Version date components: YYYY=Year, MM=Month, DD=Day */ + +#if defined(__COMO__) +# define COMPILER_ID "Comeau" + /* __COMO_VERSION__ = VRR */ +# define COMPILER_VERSION_MAJOR DEC(__COMO_VERSION__ / 100) +# define COMPILER_VERSION_MINOR DEC(__COMO_VERSION__ % 100) + +#elif defined(__INTEL_COMPILER) || defined(__ICC) +# define COMPILER_ID "Intel" + /* __INTEL_COMPILER = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER/100) +# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER % 10) +# if defined(__INTEL_COMPILER_BUILD_DATE) + /* __INTEL_COMPILER_BUILD_DATE = YYYYMMDD */ +# define COMPILER_VERSION_TWEAK DEC(__INTEL_COMPILER_BUILD_DATE) +# endif + +#elif defined(__PATHCC__) +# define COMPILER_ID "PathScale" +# define COMPILER_VERSION_MAJOR DEC(__PATHCC__) +# define COMPILER_VERSION_MINOR DEC(__PATHCC_MINOR__) +# if defined(__PATHCC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__PATHCC_PATCHLEVEL__) +# endif + +#elif defined(__clang__) +# define COMPILER_ID "Clang" +# define COMPILER_VERSION_MAJOR DEC(__clang_major__) +# define COMPILER_VERSION_MINOR DEC(__clang_minor__) +# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__) + +#elif defined(__BORLANDC__) && defined(__CODEGEARC_VERSION__) +# define COMPILER_ID "Embarcadero" +# define COMPILER_VERSION_MAJOR HEX(__CODEGEARC_VERSION__>>24 & 0x00FF) +# define COMPILER_VERSION_MINOR HEX(__CODEGEARC_VERSION__>>16 & 0x00FF) +# define COMPILER_VERSION_PATCH HEX(__CODEGEARC_VERSION__ & 0xFFFF) + +#elif defined(__BORLANDC__) +# define COMPILER_ID "Borland" + /* __BORLANDC__ = 0xVRR */ +# define COMPILER_VERSION_MAJOR HEX(__BORLANDC__>>8) +# define COMPILER_VERSION_MINOR HEX(__BORLANDC__ & 0xFF) + +#elif defined(__WATCOMC__) +# define COMPILER_ID "Watcom" + /* __WATCOMC__ = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(__WATCOMC__ / 100) +# define COMPILER_VERSION_MINOR DEC(__WATCOMC__ % 100) + +#elif defined(__SUNPRO_CC) +# define COMPILER_ID "SunPro" +# if __SUNPRO_CC >= 0x5100 + /* __SUNPRO_CC = 0xVRRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_CC>>12) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_CC>>4 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_CC & 0xF) +# else + /* __SUNPRO_CC = 0xVRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_CC>>8) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_CC>>4 & 0xF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_CC & 0xF) +# endif + +#elif defined(__HP_aCC) +# define COMPILER_ID "HP" + /* __HP_aCC = VVRRPP */ +# define COMPILER_VERSION_MAJOR DEC(__HP_aCC/10000) +# define COMPILER_VERSION_MINOR DEC(__HP_aCC/100 % 100) +# define COMPILER_VERSION_PATCH DEC(__HP_aCC % 100) + +#elif defined(__DECCXX) +# define COMPILER_ID "Compaq" + /* __DECCXX_VER = VVRRTPPPP */ +# define COMPILER_VERSION_MAJOR DEC(__DECCXX_VER/10000000) +# define COMPILER_VERSION_MINOR DEC(__DECCXX_VER/100000 % 100) +# define COMPILER_VERSION_PATCH DEC(__DECCXX_VER % 10000) + +#elif defined(__IBMCPP__) +# if defined(__COMPILER_VER__) +# define COMPILER_ID "zOS" +# else +# if __IBMCPP__ >= 800 +# define COMPILER_ID "XL" +# else +# define COMPILER_ID "VisualAge" +# endif + /* __IBMCPP__ = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__IBMCPP__/100) +# define COMPILER_VERSION_MINOR DEC(__IBMCPP__/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__IBMCPP__ % 10) +# endif + +#elif defined(__PGI) +# define COMPILER_ID "PGI" +# define COMPILER_VERSION_MAJOR DEC(__PGIC__) +# define COMPILER_VERSION_MINOR DEC(__PGIC_MINOR__) +# if defined(__PGIC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__PGIC_PATCHLEVEL__) +# endif + +#elif defined(_CRAYC) +# define COMPILER_ID "Cray" +# define COMPILER_VERSION_MAJOR DEC(_RELEASE) +# define COMPILER_VERSION_MINOR DEC(_RELEASE_MINOR) + +#elif defined(__TI_COMPILER_VERSION__) +# define COMPILER_ID "TI" + /* __TI_COMPILER_VERSION__ = VVVRRRPPP */ +# define COMPILER_VERSION_MAJOR DEC(__TI_COMPILER_VERSION__/1000000) +# define COMPILER_VERSION_MINOR DEC(__TI_COMPILER_VERSION__/1000 % 1000) +# define COMPILER_VERSION_PATCH DEC(__TI_COMPILER_VERSION__ % 1000) + +#elif defined(__SCO_VERSION__) +# define COMPILER_ID "SCO" + +#elif defined(__GNUC__) +# define COMPILER_ID "GNU" +# define COMPILER_VERSION_MAJOR DEC(__GNUC__) +# define COMPILER_VERSION_MINOR DEC(__GNUC_MINOR__) +# if defined(__GNUC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__) +# endif + +#elif defined(_MSC_VER) +# define COMPILER_ID "MSVC" + /* _MSC_VER = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(_MSC_VER / 100) +# define COMPILER_VERSION_MINOR DEC(_MSC_VER % 100) +# if defined(_MSC_FULL_VER) +# if _MSC_VER >= 1400 + /* _MSC_FULL_VER = VVRRPPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 100000) +# else + /* _MSC_FULL_VER = VVRRPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 10000) +# endif +# endif +# if defined(_MSC_BUILD) +# define COMPILER_VERSION_TWEAK DEC(_MSC_BUILD) +# endif + +/* Analog VisualDSP++ >= 4.5.6 */ +#elif defined(__VISUALDSPVERSION__) +# define COMPILER_ID "ADSP" + /* __VISUALDSPVERSION__ = 0xVVRRPP00 */ +# define COMPILER_VERSION_MAJOR HEX(__VISUALDSPVERSION__>>24) +# define COMPILER_VERSION_MINOR HEX(__VISUALDSPVERSION__>>16 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__VISUALDSPVERSION__>>8 & 0xFF) + +/* Analog VisualDSP++ < 4.5.6 */ +#elif defined(__ADSPBLACKFIN__) || defined(__ADSPTS__) || defined(__ADSP21000__) +# define COMPILER_ID "ADSP" + +/* IAR Systems compiler for embedded systems. + http://www.iar.com */ +#elif defined(__IAR_SYSTEMS_ICC__ ) || defined(__IAR_SYSTEMS_ICC) +# define COMPILER_ID "IAR" + +#elif defined(_SGI_COMPILER_VERSION) || defined(_COMPILER_VERSION) +# define COMPILER_ID "MIPSpro" +# if defined(_SGI_COMPILER_VERSION) + /* _SGI_COMPILER_VERSION = VRP */ +# define COMPILER_VERSION_MAJOR DEC(_SGI_COMPILER_VERSION/100) +# define COMPILER_VERSION_MINOR DEC(_SGI_COMPILER_VERSION/10 % 10) +# define COMPILER_VERSION_PATCH DEC(_SGI_COMPILER_VERSION % 10) +# else + /* _COMPILER_VERSION = VRP */ +# define COMPILER_VERSION_MAJOR DEC(_COMPILER_VERSION/100) +# define COMPILER_VERSION_MINOR DEC(_COMPILER_VERSION/10 % 10) +# define COMPILER_VERSION_PATCH DEC(_COMPILER_VERSION % 10) +# endif + +/* This compiler is either not known or is too old to define an + identification macro. Try to identify the platform and guess that + it is the native compiler. */ +#elif defined(__sgi) +# define COMPILER_ID "MIPSpro" + +#elif defined(__hpux) || defined(__hpua) +# define COMPILER_ID "HP" + +#else /* unknown compiler */ +# define COMPILER_ID "" + +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_compiler = "INFO" ":" "compiler[" COMPILER_ID "]"; + +/* Identify known platforms by name. */ +#if defined(__linux) || defined(__linux__) || defined(linux) +# define PLATFORM_ID "Linux" + +#elif defined(__CYGWIN__) +# define PLATFORM_ID "Cygwin" + +#elif defined(__MINGW32__) +# define PLATFORM_ID "MinGW" + +#elif defined(__APPLE__) +# define PLATFORM_ID "Darwin" + +#elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32) +# define PLATFORM_ID "Windows" + +#elif defined(__FreeBSD__) || defined(__FreeBSD) +# define PLATFORM_ID "FreeBSD" + +#elif defined(__NetBSD__) || defined(__NetBSD) +# define PLATFORM_ID "NetBSD" + +#elif defined(__OpenBSD__) || defined(__OPENBSD) +# define PLATFORM_ID "OpenBSD" + +#elif defined(__sun) || defined(sun) +# define PLATFORM_ID "SunOS" + +#elif defined(_AIX) || defined(__AIX) || defined(__AIX__) || defined(__aix) || defined(__aix__) +# define PLATFORM_ID "AIX" + +#elif defined(__sgi) || defined(__sgi__) || defined(_SGI) +# define PLATFORM_ID "IRIX" + +#elif defined(__hpux) || defined(__hpux__) +# define PLATFORM_ID "HP-UX" + +#elif defined(__HAIKU__) +# define PLATFORM_ID "Haiku" + +#elif defined(__BeOS) || defined(__BEOS__) || defined(_BEOS) +# define PLATFORM_ID "BeOS" + +#elif defined(__QNX__) || defined(__QNXNTO__) +# define PLATFORM_ID "QNX" + +#elif defined(__tru64) || defined(_tru64) || defined(__TRU64__) +# define PLATFORM_ID "Tru64" + +#elif defined(__riscos) || defined(__riscos__) +# define PLATFORM_ID "RISCos" + +#elif defined(__sinix) || defined(__sinix__) || defined(__SINIX__) +# define PLATFORM_ID "SINIX" + +#elif defined(__UNIX_SV__) +# define PLATFORM_ID "UNIX_SV" + +#elif defined(__bsdos__) +# define PLATFORM_ID "BSDOS" + +#elif defined(_MPRAS) || defined(MPRAS) +# define PLATFORM_ID "MP-RAS" + +#elif defined(__osf) || defined(__osf__) +# define PLATFORM_ID "OSF1" + +#elif defined(_SCO_SV) || defined(SCO_SV) || defined(sco_sv) +# define PLATFORM_ID "SCO_SV" + +#elif defined(__ultrix) || defined(__ultrix__) || defined(_ULTRIX) +# define PLATFORM_ID "ULTRIX" + +#elif defined(__XENIX__) || defined(_XENIX) || defined(XENIX) +# define PLATFORM_ID "Xenix" + +#else /* unknown platform */ +# define PLATFORM_ID "" + +#endif + +/* For windows compilers MSVC and Intel we can determine + the architecture of the compiler being used. This is because + the compilers do not have flags that can change the architecture, + but rather depend on which compiler is being used +*/ +#if defined(_WIN32) && defined(_MSC_VER) +# if defined(_M_IA64) +# define ARCHITECTURE_ID "IA64" + +# elif defined(_M_X64) || defined(_M_AMD64) +# define ARCHITECTURE_ID "x64" + +# elif defined(_M_IX86) +# define ARCHITECTURE_ID "X86" + +# elif defined(_M_ARM) +# define ARCHITECTURE_ID "ARM" + +# elif defined(_M_MIPS) +# define ARCHITECTURE_ID "MIPS" + +# elif defined(_M_SH) +# define ARCHITECTURE_ID "SHx" + +# else /* unknown architecture */ +# define ARCHITECTURE_ID "" +# endif + +#else +# define ARCHITECTURE_ID "" +#endif + +/* Convert integer to decimal digit literals. */ +#define DEC(n) \ + ('0' + (((n) / 10000000)%10)), \ + ('0' + (((n) / 1000000)%10)), \ + ('0' + (((n) / 100000)%10)), \ + ('0' + (((n) / 10000)%10)), \ + ('0' + (((n) / 1000)%10)), \ + ('0' + (((n) / 100)%10)), \ + ('0' + (((n) / 10)%10)), \ + ('0' + ((n) % 10)) + +/* Convert integer to hex digit literals. */ +#define HEX(n) \ + ('0' + ((n)>>28 & 0xF)), \ + ('0' + ((n)>>24 & 0xF)), \ + ('0' + ((n)>>20 & 0xF)), \ + ('0' + ((n)>>16 & 0xF)), \ + ('0' + ((n)>>12 & 0xF)), \ + ('0' + ((n)>>8 & 0xF)), \ + ('0' + ((n)>>4 & 0xF)), \ + ('0' + ((n) & 0xF)) + +/* Construct a string literal encoding the version number components. */ +#ifdef COMPILER_VERSION_MAJOR +char const info_version[] = { + 'I', 'N', 'F', 'O', ':', + 'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','[', + COMPILER_VERSION_MAJOR, +# ifdef COMPILER_VERSION_MINOR + '.', COMPILER_VERSION_MINOR, +# ifdef COMPILER_VERSION_PATCH + '.', COMPILER_VERSION_PATCH, +# ifdef COMPILER_VERSION_TWEAK + '.', COMPILER_VERSION_TWEAK, +# endif +# endif +# endif + ']','\0'}; +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_platform = "INFO" ":" "platform[" PLATFORM_ID "]"; +char const* info_arch = "INFO" ":" "arch[" ARCHITECTURE_ID "]"; + + + +/*--------------------------------------------------------------------------*/ + +int main(int argc, char* argv[]) +{ + int require = 0; + require += info_compiler[argc]; + require += info_platform[argc]; +#ifdef COMPILER_VERSION_MAJOR + require += info_version[argc]; +#endif + (void)argv; + return require; +} diff --git a/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CompilerIdCXX/a.out b/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CompilerIdCXX/a.out new file mode 100755 index 00000000..96c16077 Binary files /dev/null and b/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CompilerIdCXX/a.out differ diff --git a/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeDirectoryInformation.cmake b/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeDirectoryInformation.cmake new file mode 100644 index 00000000..debec154 --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeDirectoryInformation.cmake @@ -0,0 +1,16 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Relative path conversion top directories. +SET(CMAKE_RELATIVE_PATH_TOP_SOURCE "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4") +SET(CMAKE_RELATIVE_PATH_TOP_BINARY "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build") + +# Force unix paths in dependencies. +SET(CMAKE_FORCE_UNIX_PATHS 1) + + +# The C and CXX include file regular expressions for this directory. +SET(CMAKE_C_INCLUDE_REGEX_SCAN "^.*$") +SET(CMAKE_C_INCLUDE_REGEX_COMPLAIN "^$") +SET(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN}) +SET(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN}) diff --git a/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeOutput.log b/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeOutput.log new file mode 100644 index 00000000..fa5beeba --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeOutput.log @@ -0,0 +1,263 @@ +The system is: Linux - 4.4.0-94-generic - x86_64 +Compiling the C compiler identification source file "CMakeCCompilerId.c" succeeded. +Compiler: /usr/bin/cc +Build flags: +Id flags: + +The output was: +0 + + +Compilation of the C compiler identification source "CMakeCCompilerId.c" produced "a.out" + +The C compiler identification is GNU, found in "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CompilerIdC/a.out" + +Compiling the CXX compiler identification source file "CMakeCXXCompilerId.cpp" succeeded. +Compiler: /usr/bin/c++ +Build flags: +Id flags: + +The output was: +0 + + +Compilation of the CXX compiler identification source "CMakeCXXCompilerId.cpp" produced "a.out" + +The CXX compiler identification is GNU, found in "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles/2.8.12.2/CompilerIdCXX/a.out" + +Determining if the C compiler works passed with the following output: +Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeTmp + +Run Build Command:/usr/bin/make "cmTryCompileExec331465264/fast" +/usr/bin/make -f CMakeFiles/cmTryCompileExec331465264.dir/build.make CMakeFiles/cmTryCompileExec331465264.dir/build +make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeTmp' +/usr/bin/cmake -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeTmp/CMakeFiles" 1 +Building C object CMakeFiles/cmTryCompileExec331465264.dir/testCCompiler.c.o +/usr/bin/cc -o CMakeFiles/cmTryCompileExec331465264.dir/testCCompiler.c.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeTmp/testCCompiler.c" +Linking C executable cmTryCompileExec331465264 +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec331465264.dir/link.txt --verbose=1 +/usr/bin/cc CMakeFiles/cmTryCompileExec331465264.dir/testCCompiler.c.o -o cmTryCompileExec331465264 -rdynamic +make[1]: Leaving directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeTmp' + + +Detecting C compiler ABI info compiled with the following output: +Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeTmp + +Run Build Command:/usr/bin/make "cmTryCompileExec3068621836/fast" +/usr/bin/make -f CMakeFiles/cmTryCompileExec3068621836.dir/build.make CMakeFiles/cmTryCompileExec3068621836.dir/build +make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeTmp' +/usr/bin/cmake -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeTmp/CMakeFiles" 1 +Building C object CMakeFiles/cmTryCompileExec3068621836.dir/CMakeCCompilerABI.c.o +/usr/bin/cc -o CMakeFiles/cmTryCompileExec3068621836.dir/CMakeCCompilerABI.c.o -c /usr/share/cmake-2.8/Modules/CMakeCCompilerABI.c +Linking C executable cmTryCompileExec3068621836 +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec3068621836.dir/link.txt --verbose=1 +/usr/bin/cc -v CMakeFiles/cmTryCompileExec3068621836.dir/CMakeCCompilerABI.c.o -o cmTryCompileExec3068621836 -rdynamic +Using built-in specs. +COLLECT_GCC=/usr/bin/cc +COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/4.8/lto-wrapper +Target: x86_64-linux-gnu +Configured with: ../src/configure -v --with-pkgversion='Ubuntu 4.8.4-2ubuntu1~14.04.3' --with-bugurl=file:///usr/share/doc/gcc-4.8/README.Bugs --enable-languages=c,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-4.8 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --with-gxx-include-dir=/usr/include/c++/4.8 --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --enable-gnu-unique-object --disable-libmudflap --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-4.8-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu +Thread model: posix +gcc version 4.8.4 (Ubuntu 4.8.4-2ubuntu1~14.04.3) +COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/ +LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../:/lib/:/usr/lib/ +COLLECT_GCC_OPTIONS='-v' '-o' 'cmTryCompileExec3068621836' '-rdynamic' '-mtune=generic' '-march=x86-64' + /usr/lib/gcc/x86_64-linux-gnu/4.8/collect2 --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTryCompileExec3068621836 /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/4.8 -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../.. CMakeFiles/cmTryCompileExec3068621836.dir/CMakeCCompilerABI.c.o -lgcc --as-needed -lgcc_s --no-as-needed -lc -lgcc --as-needed -lgcc_s --no-as-needed /usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o +make[1]: Leaving directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeTmp' + + +Parsed C implicit link information from above output: + link line regex: [^( *|.*[/\])(ld|([^/\]+-)?ld|collect2)[^/\]*( |$)] + ignore line: [Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeTmp] + ignore line: [] + ignore line: [Run Build Command:/usr/bin/make "cmTryCompileExec3068621836/fast"] + ignore line: [/usr/bin/make -f CMakeFiles/cmTryCompileExec3068621836.dir/build.make CMakeFiles/cmTryCompileExec3068621836.dir/build] + ignore line: [make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeTmp'] + ignore line: [/usr/bin/cmake -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeTmp/CMakeFiles" 1] + ignore line: [Building C object CMakeFiles/cmTryCompileExec3068621836.dir/CMakeCCompilerABI.c.o] + ignore line: [/usr/bin/cc -o CMakeFiles/cmTryCompileExec3068621836.dir/CMakeCCompilerABI.c.o -c /usr/share/cmake-2.8/Modules/CMakeCCompilerABI.c] + ignore line: [Linking C executable cmTryCompileExec3068621836] + ignore line: [/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec3068621836.dir/link.txt --verbose=1] + ignore line: [/usr/bin/cc -v CMakeFiles/cmTryCompileExec3068621836.dir/CMakeCCompilerABI.c.o -o cmTryCompileExec3068621836 -rdynamic ] + ignore line: [Using built-in specs.] + ignore line: [COLLECT_GCC=/usr/bin/cc] + ignore line: [COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/4.8/lto-wrapper] + ignore line: [Target: x86_64-linux-gnu] + ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 4.8.4-2ubuntu1~14.04.3' --with-bugurl=file:///usr/share/doc/gcc-4.8/README.Bugs --enable-languages=c,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-4.8 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --with-gxx-include-dir=/usr/include/c++/4.8 --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --enable-gnu-unique-object --disable-libmudflap --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-4.8-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu] + ignore line: [Thread model: posix] + ignore line: [gcc version 4.8.4 (Ubuntu 4.8.4-2ubuntu1~14.04.3) ] + ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/] + ignore line: [LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../:/lib/:/usr/lib/] + ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'cmTryCompileExec3068621836' '-rdynamic' '-mtune=generic' '-march=x86-64'] + link line: [ /usr/lib/gcc/x86_64-linux-gnu/4.8/collect2 --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTryCompileExec3068621836 /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/4.8 -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../.. CMakeFiles/cmTryCompileExec3068621836.dir/CMakeCCompilerABI.c.o -lgcc --as-needed -lgcc_s --no-as-needed -lc -lgcc --as-needed -lgcc_s --no-as-needed /usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o] + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/collect2] ==> ignore + arg [--sysroot=/] ==> ignore + arg [--build-id] ==> ignore + arg [--eh-frame-hdr] ==> ignore + arg [-m] ==> ignore + arg [elf_x86_64] ==> ignore + arg [--hash-style=gnu] ==> ignore + arg [--as-needed] ==> ignore + arg [-export-dynamic] ==> ignore + arg [-dynamic-linker] ==> ignore + arg [/lib64/ld-linux-x86-64.so.2] ==> ignore + arg [-zrelro] ==> ignore + arg [-o] ==> ignore + arg [cmTryCompileExec3068621836] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o] ==> ignore + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] + arg [-L/lib/x86_64-linux-gnu] ==> dir [/lib/x86_64-linux-gnu] + arg [-L/lib/../lib] ==> dir [/lib/../lib] + arg [-L/usr/lib/x86_64-linux-gnu] ==> dir [/usr/lib/x86_64-linux-gnu] + arg [-L/usr/lib/../lib] ==> dir [/usr/lib/../lib] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] + arg [CMakeFiles/cmTryCompileExec3068621836.dir/CMakeCCompilerABI.c.o] ==> ignore + arg [-lgcc] ==> lib [gcc] + arg [--as-needed] ==> ignore + arg [-lgcc_s] ==> lib [gcc_s] + arg [--no-as-needed] ==> ignore + arg [-lc] ==> lib [c] + arg [-lgcc] ==> lib [gcc] + arg [--as-needed] ==> ignore + arg [-lgcc_s] ==> lib [gcc_s] + arg [--no-as-needed] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o] ==> ignore + remove lib [gcc] + remove lib [gcc_s] + remove lib [gcc] + remove lib [gcc_s] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8] ==> [/usr/lib/gcc/x86_64-linux-gnu/4.8] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] ==> [/usr/lib] + collapse library dir [/lib/x86_64-linux-gnu] ==> [/lib/x86_64-linux-gnu] + collapse library dir [/lib/../lib] ==> [/lib] + collapse library dir [/usr/lib/x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/../lib] ==> [/usr/lib] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] ==> [/usr/lib] + implicit libs: [c] + implicit dirs: [/usr/lib/gcc/x86_64-linux-gnu/4.8;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib] + implicit fwks: [] + + +Determining if the CXX compiler works passed with the following output: +Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeTmp + +Run Build Command:/usr/bin/make "cmTryCompileExec519307726/fast" +/usr/bin/make -f CMakeFiles/cmTryCompileExec519307726.dir/build.make CMakeFiles/cmTryCompileExec519307726.dir/build +make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeTmp' +/usr/bin/cmake -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeTmp/CMakeFiles" 1 +Building CXX object CMakeFiles/cmTryCompileExec519307726.dir/testCXXCompiler.cxx.o +/usr/bin/c++ -o CMakeFiles/cmTryCompileExec519307726.dir/testCXXCompiler.cxx.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeTmp/testCXXCompiler.cxx" +Linking CXX executable cmTryCompileExec519307726 +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec519307726.dir/link.txt --verbose=1 +/usr/bin/c++ CMakeFiles/cmTryCompileExec519307726.dir/testCXXCompiler.cxx.o -o cmTryCompileExec519307726 -rdynamic +make[1]: Leaving directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeTmp' + + +Detecting CXX compiler ABI info compiled with the following output: +Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeTmp + +Run Build Command:/usr/bin/make "cmTryCompileExec676125485/fast" +/usr/bin/make -f CMakeFiles/cmTryCompileExec676125485.dir/build.make CMakeFiles/cmTryCompileExec676125485.dir/build +make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeTmp' +/usr/bin/cmake -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeTmp/CMakeFiles" 1 +Building CXX object CMakeFiles/cmTryCompileExec676125485.dir/CMakeCXXCompilerABI.cpp.o +/usr/bin/c++ -o CMakeFiles/cmTryCompileExec676125485.dir/CMakeCXXCompilerABI.cpp.o -c /usr/share/cmake-2.8/Modules/CMakeCXXCompilerABI.cpp +Linking CXX executable cmTryCompileExec676125485 +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec676125485.dir/link.txt --verbose=1 +/usr/bin/c++ -v CMakeFiles/cmTryCompileExec676125485.dir/CMakeCXXCompilerABI.cpp.o -o cmTryCompileExec676125485 -rdynamic +Using built-in specs. +COLLECT_GCC=/usr/bin/c++ +COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/4.8/lto-wrapper +Target: x86_64-linux-gnu +Configured with: ../src/configure -v --with-pkgversion='Ubuntu 4.8.4-2ubuntu1~14.04.3' --with-bugurl=file:///usr/share/doc/gcc-4.8/README.Bugs --enable-languages=c,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-4.8 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --with-gxx-include-dir=/usr/include/c++/4.8 --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --enable-gnu-unique-object --disable-libmudflap --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-4.8-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu +Thread model: posix +gcc version 4.8.4 (Ubuntu 4.8.4-2ubuntu1~14.04.3) +COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/ +LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../:/lib/:/usr/lib/ +COLLECT_GCC_OPTIONS='-v' '-o' 'cmTryCompileExec676125485' '-rdynamic' '-shared-libgcc' '-mtune=generic' '-march=x86-64' + /usr/lib/gcc/x86_64-linux-gnu/4.8/collect2 --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTryCompileExec676125485 /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/4.8 -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../.. CMakeFiles/cmTryCompileExec676125485.dir/CMakeCXXCompilerABI.cpp.o -lstdc++ -lm -lgcc_s -lgcc -lc -lgcc_s -lgcc /usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o +make[1]: Leaving directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeTmp' + + +Parsed CXX implicit link information from above output: + link line regex: [^( *|.*[/\])(ld|([^/\]+-)?ld|collect2)[^/\]*( |$)] + ignore line: [Change Dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeTmp] + ignore line: [] + ignore line: [Run Build Command:/usr/bin/make "cmTryCompileExec676125485/fast"] + ignore line: [/usr/bin/make -f CMakeFiles/cmTryCompileExec676125485.dir/build.make CMakeFiles/cmTryCompileExec676125485.dir/build] + ignore line: [make[1]: Entering directory `/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeTmp'] + ignore line: [/usr/bin/cmake -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles/CMakeTmp/CMakeFiles" 1] + ignore line: [Building CXX object CMakeFiles/cmTryCompileExec676125485.dir/CMakeCXXCompilerABI.cpp.o] + ignore line: [/usr/bin/c++ -o CMakeFiles/cmTryCompileExec676125485.dir/CMakeCXXCompilerABI.cpp.o -c /usr/share/cmake-2.8/Modules/CMakeCXXCompilerABI.cpp] + ignore line: [Linking CXX executable cmTryCompileExec676125485] + ignore line: [/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTryCompileExec676125485.dir/link.txt --verbose=1] + ignore line: [/usr/bin/c++ -v CMakeFiles/cmTryCompileExec676125485.dir/CMakeCXXCompilerABI.cpp.o -o cmTryCompileExec676125485 -rdynamic ] + ignore line: [Using built-in specs.] + ignore line: [COLLECT_GCC=/usr/bin/c++] + ignore line: [COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/4.8/lto-wrapper] + ignore line: [Target: x86_64-linux-gnu] + ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 4.8.4-2ubuntu1~14.04.3' --with-bugurl=file:///usr/share/doc/gcc-4.8/README.Bugs --enable-languages=c,c++,java,go,d,fortran,objc,obj-c++ --prefix=/usr --program-suffix=-4.8 --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --with-gxx-include-dir=/usr/include/c++/4.8 --libdir=/usr/lib --enable-nls --with-sysroot=/ --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --enable-gnu-unique-object --disable-libmudflap --enable-plugin --with-system-zlib --disable-browser-plugin --enable-java-awt=gtk --enable-gtk-cairo --with-java-home=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64/jre --enable-java-home --with-jvm-root-dir=/usr/lib/jvm/java-1.5.0-gcj-4.8-amd64 --with-jvm-jar-dir=/usr/lib/jvm-exports/java-1.5.0-gcj-4.8-amd64 --with-arch-directory=amd64 --with-ecj-jar=/usr/share/java/eclipse-ecj.jar --enable-objc-gc --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --with-tune=generic --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu] + ignore line: [Thread model: posix] + ignore line: [gcc version 4.8.4 (Ubuntu 4.8.4-2ubuntu1~14.04.3) ] + ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/] + ignore line: [LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/4.8/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../:/lib/:/usr/lib/] + ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'cmTryCompileExec676125485' '-rdynamic' '-shared-libgcc' '-mtune=generic' '-march=x86-64'] + link line: [ /usr/lib/gcc/x86_64-linux-gnu/4.8/collect2 --sysroot=/ --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -export-dynamic -dynamic-linker /lib64/ld-linux-x86-64.so.2 -z relro -o cmTryCompileExec676125485 /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o -L/usr/lib/gcc/x86_64-linux-gnu/4.8 -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../.. CMakeFiles/cmTryCompileExec676125485.dir/CMakeCXXCompilerABI.cpp.o -lstdc++ -lm -lgcc_s -lgcc -lc -lgcc_s -lgcc /usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o /usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o] + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/collect2] ==> ignore + arg [--sysroot=/] ==> ignore + arg [--build-id] ==> ignore + arg [--eh-frame-hdr] ==> ignore + arg [-m] ==> ignore + arg [elf_x86_64] ==> ignore + arg [--hash-style=gnu] ==> ignore + arg [--as-needed] ==> ignore + arg [-export-dynamic] ==> ignore + arg [-dynamic-linker] ==> ignore + arg [/lib64/ld-linux-x86-64.so.2] ==> ignore + arg [-zrelro] ==> ignore + arg [-o] ==> ignore + arg [cmTryCompileExec676125485] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crt1.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crti.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/crtbegin.o] ==> ignore + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] + arg [-L/lib/x86_64-linux-gnu] ==> dir [/lib/x86_64-linux-gnu] + arg [-L/lib/../lib] ==> dir [/lib/../lib] + arg [-L/usr/lib/x86_64-linux-gnu] ==> dir [/usr/lib/x86_64-linux-gnu] + arg [-L/usr/lib/../lib] ==> dir [/usr/lib/../lib] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] + arg [CMakeFiles/cmTryCompileExec676125485.dir/CMakeCXXCompilerABI.cpp.o] ==> ignore + arg [-lstdc++] ==> lib [stdc++] + arg [-lm] ==> lib [m] + arg [-lgcc_s] ==> lib [gcc_s] + arg [-lgcc] ==> lib [gcc] + arg [-lc] ==> lib [c] + arg [-lgcc_s] ==> lib [gcc_s] + arg [-lgcc] ==> lib [gcc] + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/crtend.o] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu/crtn.o] ==> ignore + remove lib [gcc_s] + remove lib [gcc] + remove lib [gcc_s] + remove lib [gcc] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8] ==> [/usr/lib/gcc/x86_64-linux-gnu/4.8] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../../../lib] ==> [/usr/lib] + collapse library dir [/lib/x86_64-linux-gnu] ==> [/lib/x86_64-linux-gnu] + collapse library dir [/lib/../lib] ==> [/lib] + collapse library dir [/usr/lib/x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/../lib] ==> [/usr/lib] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/4.8/../../..] ==> [/usr/lib] + implicit libs: [stdc++;m;c] + implicit dirs: [/usr/lib/gcc/x86_64-linux-gnu/4.8;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib] + implicit fwks: [] + + diff --git a/vSLAM/ch9 project/0.4/build/CMakeFiles/Makefile.cmake b/vSLAM/ch9 project/0.4/build/CMakeFiles/Makefile.cmake new file mode 100644 index 00000000..241b57e2 --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/CMakeFiles/Makefile.cmake @@ -0,0 +1,79 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# The generator used is: +SET(CMAKE_DEPENDS_GENERATOR "Unix Makefiles") + +# The top level Makefile was generated from the following files: +SET(CMAKE_MAKEFILE_DEPENDS + "CMakeCache.txt" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build/SophusConfig.cmake" + "../CMakeLists.txt" + "CMakeFiles/2.8.12.2/CMakeCCompiler.cmake" + "CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake" + "CMakeFiles/2.8.12.2/CMakeSystem.cmake" + "../cmake_modules/FindG2O.cmake" + "../src/CMakeLists.txt" + "../test/CMakeLists.txt" + "/usr/local/share/OpenCV/OpenCVConfig-version.cmake" + "/usr/local/share/OpenCV/OpenCVConfig.cmake" + "/usr/local/share/OpenCV/OpenCVModules-release.cmake" + "/usr/local/share/OpenCV/OpenCVModules.cmake" + "/usr/share/cmake-2.8/Modules/CMakeCCompiler.cmake.in" + "/usr/share/cmake-2.8/Modules/CMakeCCompilerABI.c" + "/usr/share/cmake-2.8/Modules/CMakeCInformation.cmake" + "/usr/share/cmake-2.8/Modules/CMakeCXXCompiler.cmake.in" + "/usr/share/cmake-2.8/Modules/CMakeCXXCompilerABI.cpp" + "/usr/share/cmake-2.8/Modules/CMakeCXXInformation.cmake" + "/usr/share/cmake-2.8/Modules/CMakeClDeps.cmake" + "/usr/share/cmake-2.8/Modules/CMakeCommonLanguageInclude.cmake" + "/usr/share/cmake-2.8/Modules/CMakeDetermineCCompiler.cmake" + "/usr/share/cmake-2.8/Modules/CMakeDetermineCXXCompiler.cmake" + "/usr/share/cmake-2.8/Modules/CMakeDetermineCompiler.cmake" + "/usr/share/cmake-2.8/Modules/CMakeDetermineCompilerABI.cmake" + "/usr/share/cmake-2.8/Modules/CMakeDetermineCompilerId.cmake" + "/usr/share/cmake-2.8/Modules/CMakeDetermineSystem.cmake" + "/usr/share/cmake-2.8/Modules/CMakeFindBinUtils.cmake" + "/usr/share/cmake-2.8/Modules/CMakeGenericSystem.cmake" + "/usr/share/cmake-2.8/Modules/CMakeParseImplicitLinkInfo.cmake" + "/usr/share/cmake-2.8/Modules/CMakeSystem.cmake.in" + "/usr/share/cmake-2.8/Modules/CMakeSystemSpecificInformation.cmake" + "/usr/share/cmake-2.8/Modules/CMakeTestCCompiler.cmake" + "/usr/share/cmake-2.8/Modules/CMakeTestCXXCompiler.cmake" + "/usr/share/cmake-2.8/Modules/CMakeTestCompilerCommon.cmake" + "/usr/share/cmake-2.8/Modules/CMakeUnixFindMake.cmake" + "/usr/share/cmake-2.8/Modules/Compiler/GNU-C.cmake" + "/usr/share/cmake-2.8/Modules/Compiler/GNU-CXX.cmake" + "/usr/share/cmake-2.8/Modules/Compiler/GNU.cmake" + "/usr/share/cmake-2.8/Modules/MultiArchCross.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux-CXX.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux-GNU-C.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux-GNU-CXX.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux-GNU.cmake" + "/usr/share/cmake-2.8/Modules/Platform/Linux.cmake" + "/usr/share/cmake-2.8/Modules/Platform/UnixPaths.cmake" + ) + +# The corresponding makefile is: +SET(CMAKE_MAKEFILE_OUTPUTS + "Makefile" + "CMakeFiles/cmake.check_cache" + ) + +# Byproducts of CMake generate step: +SET(CMAKE_MAKEFILE_PRODUCTS + "CMakeFiles/2.8.12.2/CMakeSystem.cmake" + "CMakeFiles/2.8.12.2/CMakeCCompiler.cmake" + "CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake" + "CMakeFiles/2.8.12.2/CMakeCCompiler.cmake" + "CMakeFiles/2.8.12.2/CMakeCXXCompiler.cmake" + "CMakeFiles/CMakeDirectoryInformation.cmake" + "src/CMakeFiles/CMakeDirectoryInformation.cmake" + "test/CMakeFiles/CMakeDirectoryInformation.cmake" + ) + +# Dependency information for all targets: +SET(CMAKE_DEPEND_INFO_FILES + "src/CMakeFiles/myslam.dir/DependInfo.cmake" + "test/CMakeFiles/run_vo.dir/DependInfo.cmake" + ) diff --git a/vSLAM/ch9 project/0.4/build/CMakeFiles/Makefile2 b/vSLAM/ch9 project/0.4/build/CMakeFiles/Makefile2 new file mode 100644 index 00000000..3cf0df8a --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/CMakeFiles/Makefile2 @@ -0,0 +1,164 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Default target executed when no arguments are given to make. +default_target: all +.PHONY : default_target + +# The main recursive all target +all: +.PHONY : all + +# The main recursive preinstall target +preinstall: +.PHONY : preinstall + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4" + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" + +#============================================================================= +# Directory level rules for directory src + +# Convenience name for "all" pass in the directory. +src/all: src/CMakeFiles/myslam.dir/all +.PHONY : src/all + +# Convenience name for "clean" pass in the directory. +src/clean: src/CMakeFiles/myslam.dir/clean +.PHONY : src/clean + +# Convenience name for "preinstall" pass in the directory. +src/preinstall: +.PHONY : src/preinstall + +#============================================================================= +# Target rules for target src/CMakeFiles/myslam.dir + +# All Build rule for target. +src/CMakeFiles/myslam.dir/all: + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/depend + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/build + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles" 1 2 3 4 5 6 7 + @echo "Built target myslam" +.PHONY : src/CMakeFiles/myslam.dir/all + +# Include target in all. +all: src/CMakeFiles/myslam.dir/all +.PHONY : all + +# Build rule for subdir invocation for target. +src/CMakeFiles/myslam.dir/rule: cmake_check_build_system + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles" 7 + $(MAKE) -f CMakeFiles/Makefile2 src/CMakeFiles/myslam.dir/all + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles" 0 +.PHONY : src/CMakeFiles/myslam.dir/rule + +# Convenience name for target. +myslam: src/CMakeFiles/myslam.dir/rule +.PHONY : myslam + +# clean rule for target. +src/CMakeFiles/myslam.dir/clean: + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/clean +.PHONY : src/CMakeFiles/myslam.dir/clean + +# clean rule for target. +clean: src/CMakeFiles/myslam.dir/clean +.PHONY : clean + +#============================================================================= +# Directory level rules for directory test + +# Convenience name for "all" pass in the directory. +test/all: test/CMakeFiles/run_vo.dir/all +.PHONY : test/all + +# Convenience name for "clean" pass in the directory. +test/clean: test/CMakeFiles/run_vo.dir/clean +.PHONY : test/clean + +# Convenience name for "preinstall" pass in the directory. +test/preinstall: +.PHONY : test/preinstall + +#============================================================================= +# Target rules for target test/CMakeFiles/run_vo.dir + +# All Build rule for target. +test/CMakeFiles/run_vo.dir/all: src/CMakeFiles/myslam.dir/all + $(MAKE) -f test/CMakeFiles/run_vo.dir/build.make test/CMakeFiles/run_vo.dir/depend + $(MAKE) -f test/CMakeFiles/run_vo.dir/build.make test/CMakeFiles/run_vo.dir/build + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles" 8 + @echo "Built target run_vo" +.PHONY : test/CMakeFiles/run_vo.dir/all + +# Include target in all. +all: test/CMakeFiles/run_vo.dir/all +.PHONY : all + +# Build rule for subdir invocation for target. +test/CMakeFiles/run_vo.dir/rule: cmake_check_build_system + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles" 8 + $(MAKE) -f CMakeFiles/Makefile2 test/CMakeFiles/run_vo.dir/all + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles" 0 +.PHONY : test/CMakeFiles/run_vo.dir/rule + +# Convenience name for target. +run_vo: test/CMakeFiles/run_vo.dir/rule +.PHONY : run_vo + +# clean rule for target. +test/CMakeFiles/run_vo.dir/clean: + $(MAKE) -f test/CMakeFiles/run_vo.dir/build.make test/CMakeFiles/run_vo.dir/clean +.PHONY : test/CMakeFiles/run_vo.dir/clean + +# clean rule for target. +clean: test/CMakeFiles/run_vo.dir/clean +.PHONY : clean + +#============================================================================= +# Special targets to cleanup operation of make. + +# Special rule to run CMake to check the build system integrity. +# No rule that depends on this can have commands that come from listfiles +# because they might be regenerated. +cmake_check_build_system: + $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0 +.PHONY : cmake_check_build_system + diff --git a/vSLAM/ch9 project/0.4/build/CMakeFiles/TargetDirectories.txt b/vSLAM/ch9 project/0.4/build/CMakeFiles/TargetDirectories.txt new file mode 100644 index 00000000..2fc56344 --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/CMakeFiles/TargetDirectories.txt @@ -0,0 +1,2 @@ +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir diff --git a/vSLAM/ch9 project/0.4/build/CMakeFiles/cmake.check_cache b/vSLAM/ch9 project/0.4/build/CMakeFiles/cmake.check_cache new file mode 100644 index 00000000..3dccd731 --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/CMakeFiles/cmake.check_cache @@ -0,0 +1 @@ +# This file is generated by cmake for dependency checking of the CMakeCache.txt file diff --git a/vSLAM/ch9 project/0.4/build/CMakeFiles/progress.marks b/vSLAM/ch9 project/0.4/build/CMakeFiles/progress.marks new file mode 100644 index 00000000..45a4fb75 --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/CMakeFiles/progress.marks @@ -0,0 +1 @@ +8 diff --git a/vSLAM/ch9 project/0.4/build/Makefile b/vSLAM/ch9 project/0.4/build/Makefile new file mode 100644 index 00000000..227a1aa2 --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/Makefile @@ -0,0 +1,150 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Default target executed when no arguments are given to make. +default_target: all +.PHONY : default_target + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4" + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" + +#============================================================================= +# Targets provided globally by CMake. + +# Special rule for the target edit_cache +edit_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running interactive CMake command-line interface..." + /usr/bin/cmake -i . +.PHONY : edit_cache + +# Special rule for the target edit_cache +edit_cache/fast: edit_cache +.PHONY : edit_cache/fast + +# Special rule for the target rebuild_cache +rebuild_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake to regenerate build system..." + /usr/bin/cmake -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) +.PHONY : rebuild_cache + +# Special rule for the target rebuild_cache +rebuild_cache/fast: rebuild_cache +.PHONY : rebuild_cache/fast + +# The main all target +all: cmake_check_build_system + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles/progress.marks" + $(MAKE) -f CMakeFiles/Makefile2 all + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles" 0 +.PHONY : all + +# The main clean target +clean: + $(MAKE) -f CMakeFiles/Makefile2 clean +.PHONY : clean + +# The main clean target +clean/fast: clean +.PHONY : clean/fast + +# Prepare targets for installation. +preinstall: all + $(MAKE) -f CMakeFiles/Makefile2 preinstall +.PHONY : preinstall + +# Prepare targets for installation. +preinstall/fast: + $(MAKE) -f CMakeFiles/Makefile2 preinstall +.PHONY : preinstall/fast + +# clear depends +depend: + $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 1 +.PHONY : depend + +#============================================================================= +# Target rules for targets named myslam + +# Build rule for target. +myslam: cmake_check_build_system + $(MAKE) -f CMakeFiles/Makefile2 myslam +.PHONY : myslam + +# fast build rule for target. +myslam/fast: + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/build +.PHONY : myslam/fast + +#============================================================================= +# Target rules for targets named run_vo + +# Build rule for target. +run_vo: cmake_check_build_system + $(MAKE) -f CMakeFiles/Makefile2 run_vo +.PHONY : run_vo + +# fast build rule for target. +run_vo/fast: + $(MAKE) -f test/CMakeFiles/run_vo.dir/build.make test/CMakeFiles/run_vo.dir/build +.PHONY : run_vo/fast + +# Help Target +help: + @echo "The following are some of the valid targets for this Makefile:" + @echo "... all (the default if no target is provided)" + @echo "... clean" + @echo "... depend" + @echo "... edit_cache" + @echo "... rebuild_cache" + @echo "... myslam" + @echo "... run_vo" +.PHONY : help + + + +#============================================================================= +# Special targets to cleanup operation of make. + +# Special rule to run CMake to check the build system integrity. +# No rule that depends on this can have commands that come from listfiles +# because they might be regenerated. +cmake_check_build_system: + $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0 +.PHONY : cmake_check_build_system + diff --git a/vSLAM/ch9 project/0.4/build/cmake_install.cmake b/vSLAM/ch9 project/0.4/build/cmake_install.cmake new file mode 100644 index 00000000..c06b71e1 --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/cmake_install.cmake @@ -0,0 +1,51 @@ +# Install script for directory: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4 + +# Set the install prefix +IF(NOT DEFINED CMAKE_INSTALL_PREFIX) + SET(CMAKE_INSTALL_PREFIX "/usr/local") +ENDIF(NOT DEFINED CMAKE_INSTALL_PREFIX) +STRING(REGEX REPLACE "/$" "" CMAKE_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}") + +# Set the install configuration name. +IF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + IF(BUILD_TYPE) + STRING(REGEX REPLACE "^[^A-Za-z0-9_]+" "" + CMAKE_INSTALL_CONFIG_NAME "${BUILD_TYPE}") + ELSE(BUILD_TYPE) + SET(CMAKE_INSTALL_CONFIG_NAME "Release") + ENDIF(BUILD_TYPE) + MESSAGE(STATUS "Install configuration: \"${CMAKE_INSTALL_CONFIG_NAME}\"") +ENDIF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + +# Set the component getting installed. +IF(NOT CMAKE_INSTALL_COMPONENT) + IF(COMPONENT) + MESSAGE(STATUS "Install component: \"${COMPONENT}\"") + SET(CMAKE_INSTALL_COMPONENT "${COMPONENT}") + ELSE(COMPONENT) + SET(CMAKE_INSTALL_COMPONENT) + ENDIF(COMPONENT) +ENDIF(NOT CMAKE_INSTALL_COMPONENT) + +# Install shared libraries without execute permission? +IF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + SET(CMAKE_INSTALL_SO_NO_EXE "1") +ENDIF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + +IF(NOT CMAKE_INSTALL_LOCAL_ONLY) + # Include the install script for each subdirectory. + INCLUDE("/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src/cmake_install.cmake") + INCLUDE("/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/test/cmake_install.cmake") + +ENDIF(NOT CMAKE_INSTALL_LOCAL_ONLY) + +IF(CMAKE_INSTALL_COMPONENT) + SET(CMAKE_INSTALL_MANIFEST "install_manifest_${CMAKE_INSTALL_COMPONENT}.txt") +ELSE(CMAKE_INSTALL_COMPONENT) + SET(CMAKE_INSTALL_MANIFEST "install_manifest.txt") +ENDIF(CMAKE_INSTALL_COMPONENT) + +FILE(WRITE "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/${CMAKE_INSTALL_MANIFEST}" "") +FOREACH(file ${CMAKE_INSTALL_MANIFEST_FILES}) + FILE(APPEND "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/${CMAKE_INSTALL_MANIFEST}" "${file}\n") +ENDFOREACH(file) diff --git a/vSLAM/ch9 project/0.4/build/src/CMakeFiles/CMakeDirectoryInformation.cmake b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/CMakeDirectoryInformation.cmake new file mode 100644 index 00000000..debec154 --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/CMakeDirectoryInformation.cmake @@ -0,0 +1,16 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Relative path conversion top directories. +SET(CMAKE_RELATIVE_PATH_TOP_SOURCE "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4") +SET(CMAKE_RELATIVE_PATH_TOP_BINARY "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build") + +# Force unix paths in dependencies. +SET(CMAKE_FORCE_UNIX_PATHS 1) + + +# The C and CXX include file regular expressions for this directory. +SET(CMAKE_C_INCLUDE_REGEX_SCAN "^.*$") +SET(CMAKE_C_INCLUDE_REGEX_COMPLAIN "^$") +SET(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN}) +SET(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN}) diff --git a/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/CXX.includecache b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/CXX.includecache new file mode 100644 index 00000000..b132b5a4 --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/CXX.includecache @@ -0,0 +1,2148 @@ +#IncludeRegexLine: ^[ ]*#[ ]*(include|import)[ ]*[<"]([^">]+)([">]) + +#IncludeRegexScan: ^.*$ + +#IncludeRegexComplain: ^$ + +#IncludeRegexTransform: + +../include/myslam/camera.h +myslam/common_include.h +../include/myslam/myslam/common_include.h + +../include/myslam/common_include.h +Eigen/Core +- +Eigen/Geometry +- +sophus/se3.h +- +sophus/so3.h +- +opencv2/core/core.hpp +- +vector +- +list +- +memory +- +string +- +iostream +- +set +- +unordered_map +- +map +- + +../include/myslam/config.h +myslam/common_include.h +../include/myslam/myslam/common_include.h + +../include/myslam/frame.h +myslam/common_include.h +../include/myslam/myslam/common_include.h +myslam/camera.h +../include/myslam/myslam/camera.h + +../include/myslam/g2o_types.h +myslam/common_include.h +../include/myslam/myslam/common_include.h +camera.h +../include/myslam/camera.h +g2o/core/base_vertex.h +- +g2o/core/base_unary_edge.h +- +g2o/core/block_solver.h +- +g2o/core/optimization_algorithm_levenberg.h +- +g2o/types/sba/types_six_dof_expmap.h +- +g2o/solvers/dense/linear_solver_dense.h +- +g2o/core/robust_kernel.h +- +g2o/core/robust_kernel_impl.h +- + +../include/myslam/map.h +myslam/common_include.h +../include/myslam/myslam/common_include.h +myslam/frame.h +../include/myslam/myslam/frame.h +myslam/mappoint.h +../include/myslam/myslam/mappoint.h + +../include/myslam/mappoint.h +myslam/common_include.h +../include/myslam/myslam/common_include.h + +../include/myslam/visual_odometry.h +myslam/common_include.h +../include/myslam/myslam/common_include.h +myslam/map.h +../include/myslam/myslam/map.h +opencv2/features2d/features2d.hpp +- + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +so3.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +Eigen/Core +- +Eigen/StdVector +- +Eigen/Geometry +- + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/camera.cpp +myslam/camera.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/myslam/camera.h +myslam/config.h +- + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/config.cpp +myslam/config.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/myslam/config.h + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/frame.cpp +myslam/frame.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/myslam/frame.h + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/g2o_types.cpp +myslam/g2o_types.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/myslam/g2o_types.h + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/map.cpp +myslam/map.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/myslam/map.h + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/mappoint.cpp +myslam/common_include.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/myslam/common_include.h +myslam/mappoint.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/myslam/mappoint.h + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/visual_odometry.cpp +opencv2/highgui/highgui.hpp +- +opencv2/imgproc/imgproc.hpp +- +opencv2/calib3d/calib3d.hpp +- +algorithm +- +boost/timer.hpp +- +myslam/config.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/myslam/config.h +myslam/visual_odometry.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/myslam/visual_odometry.h +myslam/g2o_types.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/myslam/g2o_types.h + +/usr/include/eigen3/Eigen/Cholesky +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/Cholesky/LLT.h +/usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/Cholesky/LDLT.h +/usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/Cholesky/LLT_MKL.h +/usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Core/util/Macros.h +/usr/include/eigen3/Eigen/src/Core/util/Macros.h +complex +- +src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +malloc.h +- +immintrin.h +- +emmintrin.h +- +xmmintrin.h +- +pmmintrin.h +- +tmmintrin.h +- +smmintrin.h +- +nmmintrin.h +- +altivec.h +- +arm_neon.h +- +omp.h +- +cerrno +- +cstddef +- +cstdlib +- +cmath +- +cassert +- +functional +- +iosfwd +- +cstring +- +string +- +limits +- +climits +- +algorithm +- +iostream +- +intrin.h +- +new +- +src/Core/util/Constants.h +/usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/Core/util/ForwardDeclarations.h +/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/Core/util/Meta.h +/usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/Core/util/StaticAssert.h +/usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/Core/util/XprHelper.h +/usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/Core/util/Memory.h +/usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/Core/NumTraits.h +/usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/Core/MathFunctions.h +/usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/Core/GenericPacketMath.h +/usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/Core/arch/SSE/PacketMath.h +/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/Core/arch/SSE/MathFunctions.h +/usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/Core/arch/SSE/Complex.h +/usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/Core/arch/AltiVec/PacketMath.h +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/Core/arch/AltiVec/Complex.h +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/Core/arch/NEON/PacketMath.h +/usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/Core/arch/NEON/Complex.h +/usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/Core/arch/Default/Settings.h +/usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/Core/Functors.h +/usr/include/eigen3/Eigen/src/Core/Functors.h +src/Core/DenseCoeffsBase.h +/usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/Core/DenseBase.h +/usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/Core/MatrixBase.h +/usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/Core/EigenBase.h +/usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/Core/Assign.h +/usr/include/eigen3/Eigen/src/Core/Assign.h +src/Core/util/BlasUtil.h +/usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/Core/DenseStorage.h +/usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/Core/NestByValue.h +/usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/Core/ForceAlignedAccess.h +/usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/Core/ReturnByValue.h +/usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/Core/NoAlias.h +/usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/Core/PlainObjectBase.h +/usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/Core/Matrix.h +/usr/include/eigen3/Eigen/src/Core/Matrix.h +src/Core/Array.h +/usr/include/eigen3/Eigen/src/Core/Array.h +src/Core/CwiseBinaryOp.h +/usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/Core/CwiseUnaryOp.h +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/Core/CwiseNullaryOp.h +/usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/Core/CwiseUnaryView.h +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/Core/SelfCwiseBinaryOp.h +/usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/Core/Dot.h +/usr/include/eigen3/Eigen/src/Core/Dot.h +src/Core/StableNorm.h +/usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/Core/MapBase.h +/usr/include/eigen3/Eigen/src/Core/MapBase.h +src/Core/Stride.h +/usr/include/eigen3/Eigen/src/Core/Stride.h +src/Core/Map.h +/usr/include/eigen3/Eigen/src/Core/Map.h +src/Core/Block.h +/usr/include/eigen3/Eigen/src/Core/Block.h +src/Core/VectorBlock.h +/usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/Core/Ref.h +/usr/include/eigen3/Eigen/src/Core/Ref.h +src/Core/Transpose.h +/usr/include/eigen3/Eigen/src/Core/Transpose.h +src/Core/DiagonalMatrix.h +/usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/Core/Diagonal.h +/usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/Core/DiagonalProduct.h +/usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/Core/PermutationMatrix.h +/usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/Core/Transpositions.h +/usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/Core/Redux.h +/usr/include/eigen3/Eigen/src/Core/Redux.h +src/Core/Visitor.h +/usr/include/eigen3/Eigen/src/Core/Visitor.h +src/Core/Fuzzy.h +/usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/Core/IO.h +/usr/include/eigen3/Eigen/src/Core/IO.h +src/Core/Swap.h +/usr/include/eigen3/Eigen/src/Core/Swap.h +src/Core/CommaInitializer.h +/usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/Core/Flagged.h +/usr/include/eigen3/Eigen/src/Core/Flagged.h +src/Core/ProductBase.h +/usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/Core/GeneralProduct.h +/usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/Core/TriangularMatrix.h +/usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/Core/SelfAdjointView.h +/usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/Core/products/GeneralBlockPanelKernel.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/Core/products/Parallelizer.h +/usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/Core/products/CoeffBasedProduct.h +/usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/Core/products/GeneralMatrixVector.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/Core/products/GeneralMatrixMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/Core/SolveTriangular.h +/usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/Core/products/GeneralMatrixMatrixTriangular.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/Core/products/SelfadjointMatrixVector.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/Core/products/SelfadjointMatrixMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/Core/products/SelfadjointProduct.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/Core/products/SelfadjointRank2Update.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/Core/products/TriangularMatrixVector.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/Core/products/TriangularMatrixMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/Core/products/TriangularSolverMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/Core/products/TriangularSolverVector.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/Core/BandMatrix.h +/usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/Core/CoreIterators.h +/usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/Core/BooleanRedux.h +/usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/Core/Select.h +/usr/include/eigen3/Eigen/src/Core/Select.h +src/Core/VectorwiseOp.h +/usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/Core/Random.h +/usr/include/eigen3/Eigen/src/Core/Random.h +src/Core/Replicate.h +/usr/include/eigen3/Eigen/src/Core/Replicate.h +src/Core/Reverse.h +/usr/include/eigen3/Eigen/src/Core/Reverse.h +src/Core/ArrayBase.h +/usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/Core/ArrayWrapper.h +/usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/Core/products/GeneralMatrixMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/Core/products/GeneralMatrixVector_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/Core/products/SelfadjointMatrixMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/Core/products/SelfadjointMatrixVector_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/Core/products/TriangularMatrixMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/Core/products/TriangularMatrixVector_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/Core/products/TriangularSolverMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/Core/Assign_MKL.h +/usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/Core/GlobalFunctions.h +/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +Eigen2Support +/usr/include/eigen3/Eigen/Eigen2Support + +/usr/include/eigen3/Eigen/Dense +Core +/usr/include/eigen3/Eigen/Core +LU +/usr/include/eigen3/Eigen/LU +Cholesky +/usr/include/eigen3/Eigen/Cholesky +QR +/usr/include/eigen3/Eigen/QR +SVD +/usr/include/eigen3/Eigen/SVD +Geometry +/usr/include/eigen3/Eigen/Geometry +Eigenvalues +/usr/include/eigen3/Eigen/Eigenvalues + +/usr/include/eigen3/Eigen/Eigen2Support +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Eigen2Support/Macros.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/Eigen2Support/Memory.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/Eigen2Support/Meta.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/Eigen2Support/Lazy.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/Eigen2Support/Cwise.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/Eigen2Support/CwiseOperators.h +/usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/Eigen2Support/TriangularSolver.h +/usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/Eigen2Support/Block.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/Eigen2Support/VectorBlock.h +/usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/Eigen2Support/Minor.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/Eigen2Support/MathFunctions.h +/usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +iostream +- + +/usr/include/eigen3/Eigen/Eigenvalues +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +Cholesky +/usr/include/eigen3/Eigen/Cholesky +Jacobi +/usr/include/eigen3/Eigen/Jacobi +Householder +/usr/include/eigen3/Eigen/Householder +LU +/usr/include/eigen3/Eigen/LU +Geometry +/usr/include/eigen3/Eigen/Geometry +src/Eigenvalues/Tridiagonalization.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/Eigenvalues/RealSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/Eigenvalues/EigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/Eigenvalues/SelfAdjointEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/Eigenvalues/HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/Eigenvalues/ComplexSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/Eigenvalues/ComplexEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/Eigenvalues/RealQZ.h +/usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/Eigenvalues/GeneralizedEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/Eigenvalues/MatrixBaseEigenvalues.h +/usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/Eigenvalues/RealSchur_MKL.h +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/Eigenvalues/ComplexSchur_MKL.h +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Geometry +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +SVD +/usr/include/eigen3/Eigen/SVD +LU +/usr/include/eigen3/Eigen/LU +limits +- +src/Geometry/OrthoMethods.h +/usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/Geometry/EulerAngles.h +/usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/Geometry/Homogeneous.h +/usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/Geometry/RotationBase.h +/usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/Geometry/Rotation2D.h +/usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/Geometry/Quaternion.h +/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/Geometry/AngleAxis.h +/usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/Geometry/Transform.h +/usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/Geometry/Translation.h +/usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/Geometry/Scaling.h +/usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/Geometry/Hyperplane.h +/usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/Geometry/ParametrizedLine.h +/usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/Geometry/AlignedBox.h +/usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/Geometry/Umeyama.h +/usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/Geometry/arch/Geometry_SSE.h +/usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/Eigen2Support/Geometry/All.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Householder +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Householder/Householder.h +/usr/include/eigen3/Eigen/src/Householder/Householder.h +src/Householder/HouseholderSequence.h +/usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/Householder/BlockHouseholder.h +/usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Jacobi +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Jacobi/Jacobi.h +/usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/LU +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/misc/Kernel.h +/usr/include/eigen3/Eigen/src/misc/Kernel.h +src/misc/Image.h +/usr/include/eigen3/Eigen/src/misc/Image.h +src/LU/FullPivLU.h +/usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/LU/PartialPivLU.h +/usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/LU/PartialPivLU_MKL.h +/usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/LU/Determinant.h +/usr/include/eigen3/Eigen/src/LU/Determinant.h +src/LU/Inverse.h +/usr/include/eigen3/Eigen/src/LU/Inverse.h +src/LU/arch/Inverse_SSE.h +/usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/Eigen2Support/LU.h +/usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/QR +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +Cholesky +/usr/include/eigen3/Eigen/Cholesky +Jacobi +/usr/include/eigen3/Eigen/Jacobi +Householder +/usr/include/eigen3/Eigen/Householder +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/QR/HouseholderQR.h +/usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/QR/FullPivHouseholderQR.h +/usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/QR/ColPivHouseholderQR.h +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/QR/HouseholderQR_MKL.h +/usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/QR/ColPivHouseholderQR_MKL.h +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/Eigen2Support/QR.h +/usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +Eigenvalues +/usr/include/eigen3/Eigen/Eigenvalues + +/usr/include/eigen3/Eigen/SVD +QR +/usr/include/eigen3/Eigen/QR +Householder +/usr/include/eigen3/Eigen/Householder +Jacobi +/usr/include/eigen3/Eigen/Jacobi +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/SVD/JacobiSVD.h +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/SVD/JacobiSVD_MKL.h +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/SVD/UpperBidiagonalization.h +/usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/Eigen2Support/SVD.h +/usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/StdVector +Core +/usr/include/eigen3/Eigen/Core +vector +- +src/StlSupport/StdVector.h +/usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + +/usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + +/usr/include/eigen3/Eigen/src/Cholesky/LLT.h + +/usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Cholesky/Eigen/src/Core/util/MKL_support.h +iostream +- + +/usr/include/eigen3/Eigen/src/Core/Array.h + +/usr/include/eigen3/Eigen/src/Core/ArrayBase.h +../plugins/CommonCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +../plugins/MatrixCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +../plugins/ArrayCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +../plugins/CommonCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +../plugins/MatrixCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +../plugins/ArrayCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + +/usr/include/eigen3/Eigen/src/Core/Assign.h + +/usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + +/usr/include/eigen3/Eigen/src/Core/BandMatrix.h + +/usr/include/eigen3/Eigen/src/Core/Block.h + +/usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + +/usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + +/usr/include/eigen3/Eigen/src/Core/CoreIterators.h + +/usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + +/usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + +/usr/include/eigen3/Eigen/src/Core/DenseBase.h +../plugins/BlockMethods.h +/usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + +/usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + +/usr/include/eigen3/Eigen/src/Core/DenseStorage.h + +/usr/include/eigen3/Eigen/src/Core/Diagonal.h + +/usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + +/usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + +/usr/include/eigen3/Eigen/src/Core/Dot.h + +/usr/include/eigen3/Eigen/src/Core/EigenBase.h + +/usr/include/eigen3/Eigen/src/Core/Flagged.h + +/usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + +/usr/include/eigen3/Eigen/src/Core/Functors.h + +/usr/include/eigen3/Eigen/src/Core/Fuzzy.h + +/usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + +/usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + +/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + +/usr/include/eigen3/Eigen/src/Core/IO.h + +/usr/include/eigen3/Eigen/src/Core/Map.h + +/usr/include/eigen3/Eigen/src/Core/MapBase.h + +/usr/include/eigen3/Eigen/src/Core/MathFunctions.h + +/usr/include/eigen3/Eigen/src/Core/Matrix.h + +/usr/include/eigen3/Eigen/src/Core/MatrixBase.h +../plugins/CommonCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +../plugins/CommonCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +../plugins/MatrixCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +../plugins/MatrixCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/Core/NestByValue.h + +/usr/include/eigen3/Eigen/src/Core/NoAlias.h + +/usr/include/eigen3/Eigen/src/Core/NumTraits.h + +/usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + +/usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + +/usr/include/eigen3/Eigen/src/Core/ProductBase.h + +/usr/include/eigen3/Eigen/src/Core/Random.h + +/usr/include/eigen3/Eigen/src/Core/Redux.h + +/usr/include/eigen3/Eigen/src/Core/Ref.h + +/usr/include/eigen3/Eigen/src/Core/Replicate.h + +/usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + +/usr/include/eigen3/Eigen/src/Core/Reverse.h + +/usr/include/eigen3/Eigen/src/Core/Select.h + +/usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + +/usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + +/usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + +/usr/include/eigen3/Eigen/src/Core/StableNorm.h + +/usr/include/eigen3/Eigen/src/Core/Stride.h + +/usr/include/eigen3/Eigen/src/Core/Swap.h + +/usr/include/eigen3/Eigen/src/Core/Transpose.h + +/usr/include/eigen3/Eigen/src/Core/Transpositions.h + +/usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + +/usr/include/eigen3/Eigen/src/Core/VectorBlock.h + +/usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + +/usr/include/eigen3/Eigen/src/Core/Visitor.h + +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + +/usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + +/usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + +/usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + +/usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + +/usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + +/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + +/usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + +/usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + +/usr/include/eigen3/Eigen/src/Core/util/Constants.h + +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + +/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + +/usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +mkl.h +- +mkl_lapacke.h +- + +/usr/include/eigen3/Eigen/src/Core/util/Macros.h +cstdlib +- +iostream +- + +/usr/include/eigen3/Eigen/src/Core/util/Memory.h +unistd.h +- + +/usr/include/eigen3/Eigen/src/Core/util/Meta.h + +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + +/usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +limits +- +RotationBase.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +Rotation2D.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +Quaternion.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +AngleAxis.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +Transform.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +Translation.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +Scaling.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +AlignedBox.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +Hyperplane.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +ParametrizedLine.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +RotationBase.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +Rotation2D.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +Quaternion.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +AngleAxis.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +Transform.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +Translation.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +Scaling.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +AlignedBox.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +Hyperplane.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +ParametrizedLine.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/././HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/././HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +./ComplexSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +./RealSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +./RealQZ.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +./Tridiagonalization.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +./Tridiagonalization.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + +/usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + +/usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + +/usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + +/usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + +/usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + +/usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + +/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + +/usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + +/usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + +/usr/include/eigen3/Eigen/src/Geometry/Scaling.h + +/usr/include/eigen3/Eigen/src/Geometry/Transform.h + +/usr/include/eigen3/Eigen/src/Geometry/Translation.h + +/usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + +/usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + +/usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + +/usr/include/eigen3/Eigen/src/Householder/Householder.h + +/usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + +/usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + +/usr/include/eigen3/Eigen/src/LU/Determinant.h + +/usr/include/eigen3/Eigen/src/LU/FullPivLU.h + +/usr/include/eigen3/Eigen/src/LU/Inverse.h + +/usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + +/usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/LU/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/QR/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + +/usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + +/usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/QR/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/SVD/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + +/usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +Eigen/src/StlSupport/details.h +/usr/include/eigen3/Eigen/src/StlSupport/Eigen/src/StlSupport/details.h + +/usr/include/eigen3/Eigen/src/StlSupport/details.h + +/usr/include/eigen3/Eigen/src/misc/Image.h + +/usr/include/eigen3/Eigen/src/misc/Kernel.h + +/usr/include/eigen3/Eigen/src/misc/Solve.h + +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + +/usr/local/include/g2o/config.h +g2o/core/eigen_types.h +- + +/usr/local/include/g2o/core/base_binary_edge.h +iostream +- +limits +- +base_edge.h +/usr/local/include/g2o/core/base_edge.h +robust_kernel.h +/usr/local/include/g2o/core/robust_kernel.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +base_binary_edge.hpp +/usr/local/include/g2o/core/base_binary_edge.hpp + +/usr/local/include/g2o/core/base_binary_edge.hpp + +/usr/local/include/g2o/core/base_edge.h +iostream +- +limits +- +Eigen/Core +- +optimizable_graph.h +/usr/local/include/g2o/core/optimizable_graph.h + +/usr/local/include/g2o/core/base_multi_edge.h +iostream +- +iomanip +- +limits +- +Eigen/StdVector +- +base_edge.h +/usr/local/include/g2o/core/base_edge.h +robust_kernel.h +/usr/local/include/g2o/core/robust_kernel.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +base_multi_edge.hpp +/usr/local/include/g2o/core/base_multi_edge.hpp + +/usr/local/include/g2o/core/base_multi_edge.hpp + +/usr/local/include/g2o/core/base_unary_edge.h +iostream +- +cassert +- +limits +- +base_edge.h +/usr/local/include/g2o/core/base_edge.h +robust_kernel.h +/usr/local/include/g2o/core/robust_kernel.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +base_unary_edge.hpp +/usr/local/include/g2o/core/base_unary_edge.hpp + +/usr/local/include/g2o/core/base_unary_edge.hpp + +/usr/local/include/g2o/core/base_vertex.h +optimizable_graph.h +/usr/local/include/g2o/core/optimizable_graph.h +creators.h +/usr/local/include/g2o/core/creators.h +g2o/stuff/macros.h +/usr/local/include/g2o/core/g2o/stuff/macros.h +Eigen/Core +- +Eigen/Dense +- +Eigen/Cholesky +- +Eigen/StdVector +- +stack +- +base_vertex.hpp +/usr/local/include/g2o/core/base_vertex.hpp + +/usr/local/include/g2o/core/base_vertex.hpp + +/usr/local/include/g2o/core/batch_stats.h +iostream +- +vector +- +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/block_solver.h +Eigen/Core +- +solver.h +/usr/local/include/g2o/core/solver.h +linear_solver.h +/usr/local/include/g2o/core/linear_solver.h +sparse_block_matrix.h +/usr/local/include/g2o/core/sparse_block_matrix.h +sparse_block_matrix_diagonal.h +/usr/local/include/g2o/core/sparse_block_matrix_diagonal.h +openmp_mutex.h +/usr/local/include/g2o/core/openmp_mutex.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +block_solver.hpp +/usr/local/include/g2o/core/block_solver.hpp + +/usr/local/include/g2o/core/block_solver.hpp +sparse_optimizer.h +/usr/local/include/g2o/core/sparse_optimizer.h +Eigen/LU +- +fstream +- +iomanip +- +g2o/stuff/timeutil.h +/usr/local/include/g2o/core/g2o/stuff/timeutil.h +g2o/stuff/macros.h +/usr/local/include/g2o/core/g2o/stuff/macros.h +g2o/stuff/misc.h +/usr/local/include/g2o/core/g2o/stuff/misc.h + +/usr/local/include/g2o/core/creators.h +hyper_graph.h +/usr/local/include/g2o/core/hyper_graph.h +string +- +typeinfo +- + +/usr/local/include/g2o/core/eigen_types.h +Eigen/Core +- +Eigen/Geometry +- + +/usr/local/include/g2o/core/g2o_core_api.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h + +/usr/local/include/g2o/core/hyper_graph.h +map +- +set +- +bitset +- +cassert +- +vector +- +limits +- +cstddef +- +unordered_map +- +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/jacobian_workspace.h +Eigen/Core +- +Eigen/StdVector +- +vector +- +cassert +- +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h +hyper_graph.h +/usr/local/include/g2o/core/hyper_graph.h + +/usr/local/include/g2o/core/linear_solver.h +sparse_block_matrix.h +/usr/local/include/g2o/core/sparse_block_matrix.h +sparse_block_matrix_ccs.h +/usr/local/include/g2o/core/sparse_block_matrix_ccs.h + +/usr/local/include/g2o/core/matrix_operations.h +Eigen/Core +- + +/usr/local/include/g2o/core/matrix_structure.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/openmp_mutex.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +omp.h +- +cassert +- + +/usr/local/include/g2o/core/optimizable_graph.h +set +- +iostream +- +list +- +limits +- +cmath +- +typeinfo +- +openmp_mutex.h +/usr/local/include/g2o/core/openmp_mutex.h +hyper_graph.h +/usr/local/include/g2o/core/hyper_graph.h +parameter.h +/usr/local/include/g2o/core/parameter.h +parameter_container.h +/usr/local/include/g2o/core/parameter_container.h +jacobian_workspace.h +/usr/local/include/g2o/core/jacobian_workspace.h +g2o/stuff/macros.h +/usr/local/include/g2o/core/g2o/stuff/macros.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/optimization_algorithm.h +vector +- +utility +- +iosfwd +- +g2o/stuff/property.h +/usr/local/include/g2o/core/g2o/stuff/property.h +hyper_graph.h +/usr/local/include/g2o/core/hyper_graph.h +sparse_block_matrix.h +/usr/local/include/g2o/core/sparse_block_matrix.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/optimization_algorithm_levenberg.h +optimization_algorithm_with_hessian.h +/usr/local/include/g2o/core/optimization_algorithm_with_hessian.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/optimization_algorithm_with_hessian.h +optimization_algorithm.h +/usr/local/include/g2o/core/optimization_algorithm.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/parameter.h +iosfwd +- +hyper_graph.h +/usr/local/include/g2o/core/hyper_graph.h + +/usr/local/include/g2o/core/parameter_container.h +iosfwd +- +map +- +string +- + +/usr/local/include/g2o/core/robust_kernel.h +memory +- +Eigen/Core +- +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/robust_kernel_impl.h +robust_kernel.h +/usr/local/include/g2o/core/robust_kernel.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h + +/usr/local/include/g2o/core/solver.h +hyper_graph.h +/usr/local/include/g2o/core/hyper_graph.h +batch_stats.h +/usr/local/include/g2o/core/batch_stats.h +sparse_block_matrix.h +/usr/local/include/g2o/core/sparse_block_matrix.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h +cstddef +- + +/usr/local/include/g2o/core/sparse_block_matrix.h +map +- +vector +- +fstream +- +iostream +- +iomanip +- +cassert +- +Eigen/Core +- +sparse_block_matrix_ccs.h +/usr/local/include/g2o/core/sparse_block_matrix_ccs.h +matrix_structure.h +/usr/local/include/g2o/core/matrix_structure.h +matrix_operations.h +/usr/local/include/g2o/core/matrix_operations.h +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +sparse_block_matrix.hpp +/usr/local/include/g2o/core/sparse_block_matrix.hpp + +/usr/local/include/g2o/core/sparse_block_matrix.hpp + +/usr/local/include/g2o/core/sparse_block_matrix_ccs.h +vector +- +cassert +- +Eigen/Core +- +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +matrix_operations.h +/usr/local/include/g2o/core/matrix_operations.h +unordered_map +- + +/usr/local/include/g2o/core/sparse_block_matrix_diagonal.h +vector +- +Eigen/Core +- +Eigen/StdVector +- +g2o/config.h +/usr/local/include/g2o/core/g2o/config.h +matrix_operations.h +/usr/local/include/g2o/core/matrix_operations.h + +/usr/local/include/g2o/core/sparse_optimizer.h +g2o/stuff/macros.h +/usr/local/include/g2o/core/g2o/stuff/macros.h +optimizable_graph.h +/usr/local/include/g2o/core/optimizable_graph.h +sparse_block_matrix.h +/usr/local/include/g2o/core/sparse_block_matrix.h +g2o_core_api.h +/usr/local/include/g2o/core/g2o_core_api.h +batch_stats.h +/usr/local/include/g2o/core/batch_stats.h +map +- + +/usr/local/include/g2o/solvers/dense/linear_solver_dense.h +g2o/core/linear_solver.h +/usr/local/include/g2o/solvers/dense/g2o/core/linear_solver.h +g2o/core/batch_stats.h +/usr/local/include/g2o/solvers/dense/g2o/core/batch_stats.h +vector +- +utility +- +Eigen/Core +- +Eigen/Cholesky +- + +/usr/local/include/g2o/stuff/g2o_stuff_api.h +g2o/config.h +/usr/local/include/g2o/stuff/g2o/config.h + +/usr/local/include/g2o/stuff/macros.h +float.h +- +math.h +- + +/usr/local/include/g2o/stuff/misc.h +macros.h +/usr/local/include/g2o/stuff/macros.h +cmath +- + +/usr/local/include/g2o/stuff/property.h +string +- +map +- +sstream +- +string_tools.h +/usr/local/include/g2o/stuff/string_tools.h +g2o_stuff_api.h +/usr/local/include/g2o/stuff/g2o_stuff_api.h + +/usr/local/include/g2o/stuff/string_tools.h +string +- +sstream +- +cstdlib +- +vector +- +macros.h +/usr/local/include/g2o/stuff/macros.h +g2o_stuff_api.h +/usr/local/include/g2o/stuff/g2o_stuff_api.h + +/usr/local/include/g2o/stuff/timeutil.h +time.h +- +sys/time.h +- +string +- +g2o_stuff_api.h +/usr/local/include/g2o/stuff/g2o_stuff_api.h + +/usr/local/include/g2o/types/sba/g2o_types_sba_api.h +g2o/config.h +/usr/local/include/g2o/types/sba/g2o/config.h + +/usr/local/include/g2o/types/sba/sbacam.h +Eigen/Core +- +Eigen/Geometry +- +g2o/stuff/misc.h +/usr/local/include/g2o/types/sba/g2o/stuff/misc.h +g2o/stuff/macros.h +/usr/local/include/g2o/types/sba/g2o/stuff/macros.h +g2o/types/slam3d/se3quat.h +/usr/local/include/g2o/types/sba/g2o/types/slam3d/se3quat.h +g2o_types_sba_api.h +/usr/local/include/g2o/types/sba/g2o_types_sba_api.h + +/usr/local/include/g2o/types/sba/types_sba.h +g2o/core/base_vertex.h +/usr/local/include/g2o/types/sba/g2o/core/base_vertex.h +g2o/core/base_binary_edge.h +/usr/local/include/g2o/types/sba/g2o/core/base_binary_edge.h +g2o/core/base_multi_edge.h +/usr/local/include/g2o/types/sba/g2o/core/base_multi_edge.h +sbacam.h +/usr/local/include/g2o/types/sba/sbacam.h +Eigen/Geometry +- +iostream +- +g2o_types_sba_api.h +/usr/local/include/g2o/types/sba/g2o_types_sba_api.h + +/usr/local/include/g2o/types/sba/types_six_dof_expmap.h +g2o/core/base_vertex.h +/usr/local/include/g2o/types/sba/g2o/core/base_vertex.h +g2o/core/base_binary_edge.h +/usr/local/include/g2o/types/sba/g2o/core/base_binary_edge.h +g2o/types/slam3d/se3_ops.h +/usr/local/include/g2o/types/sba/g2o/types/slam3d/se3_ops.h +types_sba.h +/usr/local/include/g2o/types/sba/types_sba.h +Eigen/Geometry +- + +/usr/local/include/g2o/types/slam3d/g2o_types_slam3d_api.h +g2o/config.h +/usr/local/include/g2o/types/slam3d/g2o/config.h + +/usr/local/include/g2o/types/slam3d/se3_ops.h +Eigen/Core +- +Eigen/Geometry +- +g2o_types_slam3d_api.h +/usr/local/include/g2o/types/slam3d/g2o_types_slam3d_api.h +se3_ops.hpp +/usr/local/include/g2o/types/slam3d/se3_ops.hpp + +/usr/local/include/g2o/types/slam3d/se3_ops.hpp + +/usr/local/include/g2o/types/slam3d/se3quat.h +se3_ops.h +/usr/local/include/g2o/types/slam3d/se3_ops.h +Eigen/Core +- +Eigen/Geometry +- + +/usr/local/include/opencv/cxcore.h +opencv2/core/core_c.h +/usr/local/include/opencv/opencv2/core/core_c.h + +/usr/local/include/opencv2/calib3d.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/opencv2/features2d.hpp +opencv2/core/affine.hpp +/usr/local/include/opencv2/opencv2/core/affine.hpp +opencv2/calib3d/calib3d_c.h +/usr/local/include/opencv2/opencv2/calib3d/calib3d_c.h + +/usr/local/include/opencv2/calib3d/calib3d.hpp +opencv2/calib3d.hpp +/usr/local/include/opencv2/calib3d/opencv2/calib3d.hpp + +/usr/local/include/opencv2/calib3d/calib3d_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/calib3d/opencv2/core/core_c.h + +/usr/local/include/opencv2/core.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/opencv2/core/cvdef.h +opencv2/core/version.hpp +/usr/local/include/opencv2/opencv2/core/version.hpp +opencv2/core/base.hpp +/usr/local/include/opencv2/opencv2/core/base.hpp +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/opencv2/core/cvstd.hpp +opencv2/core/traits.hpp +/usr/local/include/opencv2/opencv2/core/traits.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/opencv2/core/matx.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/opencv2/core/types.hpp +opencv2/core/mat.hpp +/usr/local/include/opencv2/opencv2/core/mat.hpp +opencv2/core/persistence.hpp +/usr/local/include/opencv2/opencv2/core/persistence.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/opencv2/opencv.hpp +opencv2/xfeatures2d.hpp +/usr/local/include/opencv2/opencv2/xfeatures2d.hpp +opencv2/core/operations.hpp +/usr/local/include/opencv2/opencv2/core/operations.hpp +opencv2/core/cvstd.inl.hpp +/usr/local/include/opencv2/opencv2/core/cvstd.inl.hpp +opencv2/core/utility.hpp +/usr/local/include/opencv2/opencv2/core/utility.hpp +opencv2/core/optim.hpp +/usr/local/include/opencv2/opencv2/core/optim.hpp + +/usr/local/include/opencv2/core/affine.hpp +opencv2/core.hpp +- + +/usr/local/include/opencv2/core/base.hpp +climits +- +algorithm +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/core/opencv2/core/cvstd.hpp +opencv2/core/neon_utils.hpp +/usr/local/include/opencv2/core/opencv2/core/neon_utils.hpp + +/usr/local/include/opencv2/core/bufferpool.hpp + +/usr/local/include/opencv2/core/core.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/core_c.h +opencv2/core/types_c.h +/usr/local/include/opencv2/core/opencv2/core/types_c.h +cxcore.h +/usr/local/include/opencv2/core/cxcore.h +cxcore.h +/usr/local/include/opencv2/core/cxcore.h +opencv2/core/utility.hpp +/usr/local/include/opencv2/core/opencv2/core/utility.hpp + +/usr/local/include/opencv2/core/cvdef.h +limits.h +- +opencv2/core/hal/interface.h +/usr/local/include/opencv2/core/opencv2/core/hal/interface.h +emmintrin.h +- +pmmintrin.h +- +tmmintrin.h +- +smmintrin.h +- +nmmintrin.h +- +nmmintrin.h +- +popcntintrin.h +- +immintrin.h +- +immintrin.h +- +Intrin.h +- +arm_neon.h +/usr/local/include/opencv2/core/arm_neon.h +arm_neon.h +- +intrin.h +- + +/usr/local/include/opencv2/core/cvstd.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +cstddef +- +cstring +- +cctype +- +string +- +algorithm +- +utility +- +cstdlib +- +cmath +- +opencv2/core/ptr.inl.hpp +/usr/local/include/opencv2/core/opencv2/core/ptr.inl.hpp + +/usr/local/include/opencv2/core/cvstd.inl.hpp +complex +- +ostream +- + +/usr/local/include/opencv2/core/fast_math.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +fastmath.h +- +cmath +- +math.h +- +tegra_round.hpp +/usr/local/include/opencv2/core/tegra_round.hpp + +/usr/local/include/opencv2/core/hal/interface.h +cstddef +- +stddef.h +- +cstdint +- +stdint.h +- + +/usr/local/include/opencv2/core/mat.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/core/opencv2/core/matx.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/core/opencv2/core/types.hpp +opencv2/core/bufferpool.hpp +/usr/local/include/opencv2/core/opencv2/core/bufferpool.hpp +opencv2/core/mat.inl.hpp +/usr/local/include/opencv2/core/opencv2/core/mat.inl.hpp + +/usr/local/include/opencv2/core/mat.inl.hpp + +/usr/local/include/opencv2/core/matx.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/base.hpp +/usr/local/include/opencv2/core/opencv2/core/base.hpp +opencv2/core/traits.hpp +/usr/local/include/opencv2/core/opencv2/core/traits.hpp +opencv2/core/saturate.hpp +/usr/local/include/opencv2/core/opencv2/core/saturate.hpp + +/usr/local/include/opencv2/core/neon_utils.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h + +/usr/local/include/opencv2/core/operations.hpp +cstdio +- + +/usr/local/include/opencv2/core/optim.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/persistence.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/core/opencv2/core/types.hpp +opencv2/core/mat.hpp +/usr/local/include/opencv2/core/opencv2/core/mat.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/core/opencv2/opencv.hpp +time.h +- + +/usr/local/include/opencv2/core/ptr.inl.hpp +algorithm +- + +/usr/local/include/opencv2/core/saturate.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/fast_math.hpp +/usr/local/include/opencv2/core/opencv2/core/fast_math.hpp + +/usr/local/include/opencv2/core/traits.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h + +/usr/local/include/opencv2/core/types.hpp +climits +- +cfloat +- +vector +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/core/opencv2/core/cvstd.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/core/opencv2/core/matx.hpp + +/usr/local/include/opencv2/core/types_c.h +ipl.h +- +ipl/ipl.h +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +assert.h +- +stdlib.h +- +string.h +- +float.h +- +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/utility.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp +opencv2/core/core_c.h +/usr/local/include/opencv2/core/opencv2/core/core_c.h + +/usr/local/include/opencv2/core/version.hpp + +/usr/local/include/opencv2/features2d.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/flann/miniflann.hpp +/usr/local/include/opencv2/opencv2/flann/miniflann.hpp + +/usr/local/include/opencv2/features2d/features2d.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/features2d/opencv2/features2d.hpp + +/usr/local/include/opencv2/flann/config.h + +/usr/local/include/opencv2/flann/defines.h +config.h +/usr/local/include/opencv2/flann/config.h + +/usr/local/include/opencv2/flann/miniflann.hpp +opencv2/core.hpp +/usr/local/include/opencv2/flann/opencv2/core.hpp +opencv2/flann/defines.h +/usr/local/include/opencv2/flann/opencv2/flann/defines.h + +/usr/local/include/opencv2/highgui.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgcodecs.hpp +/usr/local/include/opencv2/opencv2/imgcodecs.hpp +opencv2/videoio.hpp +/usr/local/include/opencv2/opencv2/videoio.hpp +opencv2/highgui/highgui_c.h +/usr/local/include/opencv2/opencv2/highgui/highgui_c.h + +/usr/local/include/opencv2/highgui/highgui.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/highgui/opencv2/highgui.hpp + +/usr/local/include/opencv2/highgui/highgui_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/highgui/opencv2/core/core_c.h +opencv2/imgproc/imgproc_c.h +/usr/local/include/opencv2/highgui/opencv2/imgproc/imgproc_c.h +opencv2/imgcodecs/imgcodecs_c.h +/usr/local/include/opencv2/highgui/opencv2/imgcodecs/imgcodecs_c.h +opencv2/videoio/videoio_c.h +/usr/local/include/opencv2/highgui/opencv2/videoio/videoio_c.h + +/usr/local/include/opencv2/imgcodecs.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/opencv.hpp +- + +/usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/imgcodecs/opencv2/core/core_c.h + +/usr/local/include/opencv2/imgproc.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/core.hpp +- +opencv2/imgproc.hpp +- +opencv2/imgcodecs.hpp +- +opencv2/highgui.hpp +- +iostream +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +math.h +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/opencv2/highgui.hpp +opencv2/imgproc/imgproc_c.h +/usr/local/include/opencv2/opencv2/imgproc/imgproc_c.h + +/usr/local/include/opencv2/imgproc/imgproc.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/imgproc/opencv2/imgproc.hpp + +/usr/local/include/opencv2/imgproc/imgproc_c.h +opencv2/imgproc/types_c.h +/usr/local/include/opencv2/imgproc/opencv2/imgproc/types_c.h + +/usr/local/include/opencv2/imgproc/types_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/imgproc/opencv2/core/core_c.h + +/usr/local/include/opencv2/ml.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +float.h +- +map +- +iostream +- + +/usr/local/include/opencv2/objdetect.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/objdetect/detection_based_tracker.hpp +/usr/local/include/opencv2/opencv2/objdetect/detection_based_tracker.hpp +opencv2/objdetect/objdetect_c.h +/usr/local/include/opencv2/opencv2/objdetect/objdetect_c.h + +/usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +vector +- + +/usr/local/include/opencv2/objdetect/objdetect_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/objdetect/opencv2/core/core_c.h +deque +- +vector +- + +/usr/local/include/opencv2/opencv.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/photo.hpp +/usr/local/include/opencv2/opencv2/photo.hpp +opencv2/video.hpp +/usr/local/include/opencv2/opencv2/video.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/opencv2/features2d.hpp +opencv2/objdetect.hpp +/usr/local/include/opencv2/opencv2/objdetect.hpp +opencv2/calib3d.hpp +/usr/local/include/opencv2/opencv2/calib3d.hpp +opencv2/imgcodecs.hpp +/usr/local/include/opencv2/opencv2/imgcodecs.hpp +opencv2/videoio.hpp +/usr/local/include/opencv2/opencv2/videoio.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/opencv2/highgui.hpp +opencv2/ml.hpp +/usr/local/include/opencv2/opencv2/ml.hpp + +/usr/local/include/opencv2/photo.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/photo/photo_c.h +/usr/local/include/opencv2/opencv2/photo/photo_c.h + +/usr/local/include/opencv2/photo/photo_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/photo/opencv2/core/core_c.h + +/usr/local/include/opencv2/video.hpp +opencv2/video/tracking.hpp +/usr/local/include/opencv2/opencv2/video/tracking.hpp +opencv2/video/background_segm.hpp +/usr/local/include/opencv2/opencv2/video/background_segm.hpp +opencv2/video/tracking_c.h +/usr/local/include/opencv2/opencv2/video/tracking_c.h + +/usr/local/include/opencv2/video/background_segm.hpp +opencv2/core.hpp +/usr/local/include/opencv2/video/opencv2/core.hpp + +/usr/local/include/opencv2/video/tracking.hpp +opencv2/core.hpp +/usr/local/include/opencv2/video/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/video/opencv2/imgproc.hpp + +/usr/local/include/opencv2/video/tracking_c.h +opencv2/imgproc/types_c.h +/usr/local/include/opencv2/video/opencv2/imgproc/types_c.h + +/usr/local/include/opencv2/videoio.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/opencv2/opencv.hpp + +/usr/local/include/opencv2/videoio/videoio_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/videoio/opencv2/core/core_c.h + diff --git a/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/DependInfo.cmake b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/DependInfo.cmake new file mode 100644 index 00000000..5eac2596 --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/DependInfo.cmake @@ -0,0 +1,31 @@ +# The set of languages for which implicit dependencies are needed: +SET(CMAKE_DEPENDS_LANGUAGES + "CXX" + ) +# The set of files for implicit dependencies of each language: +SET(CMAKE_DEPENDS_CHECK_CXX + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/camera.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/camera.cpp.o" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/config.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/config.cpp.o" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/frame.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/frame.cpp.o" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/g2o_types.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/g2o_types.cpp.o" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/map.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/map.cpp.o" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/mappoint.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/mappoint.cpp.o" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/visual_odometry.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/visual_odometry.cpp.o" + ) +SET(CMAKE_CXX_COMPILER_ID "GNU") + +# Targets to which this target links. +SET(CMAKE_TARGET_LINKED_INFO_FILES + ) + +# The include file search paths: +SET(CMAKE_C_TARGET_INCLUDE_PATH + "/usr/include/eigen3" + "/usr/local/include/opencv" + "/usr/local/include" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus" + "../include" + ) +SET(CMAKE_CXX_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) +SET(CMAKE_Fortran_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) +SET(CMAKE_ASM_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) diff --git a/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/build.make b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/build.make new file mode 100644 index 00000000..76420e27 --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/build.make @@ -0,0 +1,285 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4" + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" + +# Include any dependencies generated for this target. +include src/CMakeFiles/myslam.dir/depend.make + +# Include the progress variables for this target. +include src/CMakeFiles/myslam.dir/progress.make + +# Include the compile flags for this target's objects. +include src/CMakeFiles/myslam.dir/flags.make + +src/CMakeFiles/myslam.dir/frame.cpp.o: src/CMakeFiles/myslam.dir/flags.make +src/CMakeFiles/myslam.dir/frame.cpp.o: ../src/frame.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles" $(CMAKE_PROGRESS_1) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object src/CMakeFiles/myslam.dir/frame.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/myslam.dir/frame.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/frame.cpp" + +src/CMakeFiles/myslam.dir/frame.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/myslam.dir/frame.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/frame.cpp" > CMakeFiles/myslam.dir/frame.cpp.i + +src/CMakeFiles/myslam.dir/frame.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/myslam.dir/frame.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/frame.cpp" -o CMakeFiles/myslam.dir/frame.cpp.s + +src/CMakeFiles/myslam.dir/frame.cpp.o.requires: +.PHONY : src/CMakeFiles/myslam.dir/frame.cpp.o.requires + +src/CMakeFiles/myslam.dir/frame.cpp.o.provides: src/CMakeFiles/myslam.dir/frame.cpp.o.requires + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/frame.cpp.o.provides.build +.PHONY : src/CMakeFiles/myslam.dir/frame.cpp.o.provides + +src/CMakeFiles/myslam.dir/frame.cpp.o.provides.build: src/CMakeFiles/myslam.dir/frame.cpp.o + +src/CMakeFiles/myslam.dir/mappoint.cpp.o: src/CMakeFiles/myslam.dir/flags.make +src/CMakeFiles/myslam.dir/mappoint.cpp.o: ../src/mappoint.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles" $(CMAKE_PROGRESS_2) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object src/CMakeFiles/myslam.dir/mappoint.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/myslam.dir/mappoint.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/mappoint.cpp" + +src/CMakeFiles/myslam.dir/mappoint.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/myslam.dir/mappoint.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/mappoint.cpp" > CMakeFiles/myslam.dir/mappoint.cpp.i + +src/CMakeFiles/myslam.dir/mappoint.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/myslam.dir/mappoint.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/mappoint.cpp" -o CMakeFiles/myslam.dir/mappoint.cpp.s + +src/CMakeFiles/myslam.dir/mappoint.cpp.o.requires: +.PHONY : src/CMakeFiles/myslam.dir/mappoint.cpp.o.requires + +src/CMakeFiles/myslam.dir/mappoint.cpp.o.provides: src/CMakeFiles/myslam.dir/mappoint.cpp.o.requires + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/mappoint.cpp.o.provides.build +.PHONY : src/CMakeFiles/myslam.dir/mappoint.cpp.o.provides + +src/CMakeFiles/myslam.dir/mappoint.cpp.o.provides.build: src/CMakeFiles/myslam.dir/mappoint.cpp.o + +src/CMakeFiles/myslam.dir/map.cpp.o: src/CMakeFiles/myslam.dir/flags.make +src/CMakeFiles/myslam.dir/map.cpp.o: ../src/map.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles" $(CMAKE_PROGRESS_3) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object src/CMakeFiles/myslam.dir/map.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/myslam.dir/map.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/map.cpp" + +src/CMakeFiles/myslam.dir/map.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/myslam.dir/map.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/map.cpp" > CMakeFiles/myslam.dir/map.cpp.i + +src/CMakeFiles/myslam.dir/map.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/myslam.dir/map.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/map.cpp" -o CMakeFiles/myslam.dir/map.cpp.s + +src/CMakeFiles/myslam.dir/map.cpp.o.requires: +.PHONY : src/CMakeFiles/myslam.dir/map.cpp.o.requires + +src/CMakeFiles/myslam.dir/map.cpp.o.provides: src/CMakeFiles/myslam.dir/map.cpp.o.requires + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/map.cpp.o.provides.build +.PHONY : src/CMakeFiles/myslam.dir/map.cpp.o.provides + +src/CMakeFiles/myslam.dir/map.cpp.o.provides.build: src/CMakeFiles/myslam.dir/map.cpp.o + +src/CMakeFiles/myslam.dir/camera.cpp.o: src/CMakeFiles/myslam.dir/flags.make +src/CMakeFiles/myslam.dir/camera.cpp.o: ../src/camera.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles" $(CMAKE_PROGRESS_4) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object src/CMakeFiles/myslam.dir/camera.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/myslam.dir/camera.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/camera.cpp" + +src/CMakeFiles/myslam.dir/camera.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/myslam.dir/camera.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/camera.cpp" > CMakeFiles/myslam.dir/camera.cpp.i + +src/CMakeFiles/myslam.dir/camera.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/myslam.dir/camera.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/camera.cpp" -o CMakeFiles/myslam.dir/camera.cpp.s + +src/CMakeFiles/myslam.dir/camera.cpp.o.requires: +.PHONY : src/CMakeFiles/myslam.dir/camera.cpp.o.requires + +src/CMakeFiles/myslam.dir/camera.cpp.o.provides: src/CMakeFiles/myslam.dir/camera.cpp.o.requires + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/camera.cpp.o.provides.build +.PHONY : src/CMakeFiles/myslam.dir/camera.cpp.o.provides + +src/CMakeFiles/myslam.dir/camera.cpp.o.provides.build: src/CMakeFiles/myslam.dir/camera.cpp.o + +src/CMakeFiles/myslam.dir/config.cpp.o: src/CMakeFiles/myslam.dir/flags.make +src/CMakeFiles/myslam.dir/config.cpp.o: ../src/config.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles" $(CMAKE_PROGRESS_5) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object src/CMakeFiles/myslam.dir/config.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/myslam.dir/config.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/config.cpp" + +src/CMakeFiles/myslam.dir/config.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/myslam.dir/config.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/config.cpp" > CMakeFiles/myslam.dir/config.cpp.i + +src/CMakeFiles/myslam.dir/config.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/myslam.dir/config.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/config.cpp" -o CMakeFiles/myslam.dir/config.cpp.s + +src/CMakeFiles/myslam.dir/config.cpp.o.requires: +.PHONY : src/CMakeFiles/myslam.dir/config.cpp.o.requires + +src/CMakeFiles/myslam.dir/config.cpp.o.provides: src/CMakeFiles/myslam.dir/config.cpp.o.requires + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/config.cpp.o.provides.build +.PHONY : src/CMakeFiles/myslam.dir/config.cpp.o.provides + +src/CMakeFiles/myslam.dir/config.cpp.o.provides.build: src/CMakeFiles/myslam.dir/config.cpp.o + +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: src/CMakeFiles/myslam.dir/flags.make +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: ../src/g2o_types.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles" $(CMAKE_PROGRESS_6) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object src/CMakeFiles/myslam.dir/g2o_types.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/myslam.dir/g2o_types.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/g2o_types.cpp" + +src/CMakeFiles/myslam.dir/g2o_types.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/myslam.dir/g2o_types.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/g2o_types.cpp" > CMakeFiles/myslam.dir/g2o_types.cpp.i + +src/CMakeFiles/myslam.dir/g2o_types.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/myslam.dir/g2o_types.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/g2o_types.cpp" -o CMakeFiles/myslam.dir/g2o_types.cpp.s + +src/CMakeFiles/myslam.dir/g2o_types.cpp.o.requires: +.PHONY : src/CMakeFiles/myslam.dir/g2o_types.cpp.o.requires + +src/CMakeFiles/myslam.dir/g2o_types.cpp.o.provides: src/CMakeFiles/myslam.dir/g2o_types.cpp.o.requires + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/g2o_types.cpp.o.provides.build +.PHONY : src/CMakeFiles/myslam.dir/g2o_types.cpp.o.provides + +src/CMakeFiles/myslam.dir/g2o_types.cpp.o.provides.build: src/CMakeFiles/myslam.dir/g2o_types.cpp.o + +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: src/CMakeFiles/myslam.dir/flags.make +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../src/visual_odometry.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles" $(CMAKE_PROGRESS_7) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object src/CMakeFiles/myslam.dir/visual_odometry.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/myslam.dir/visual_odometry.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/visual_odometry.cpp" + +src/CMakeFiles/myslam.dir/visual_odometry.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/myslam.dir/visual_odometry.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/visual_odometry.cpp" > CMakeFiles/myslam.dir/visual_odometry.cpp.i + +src/CMakeFiles/myslam.dir/visual_odometry.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/myslam.dir/visual_odometry.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/visual_odometry.cpp" -o CMakeFiles/myslam.dir/visual_odometry.cpp.s + +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o.requires: +.PHONY : src/CMakeFiles/myslam.dir/visual_odometry.cpp.o.requires + +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o.provides: src/CMakeFiles/myslam.dir/visual_odometry.cpp.o.requires + $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/visual_odometry.cpp.o.provides.build +.PHONY : src/CMakeFiles/myslam.dir/visual_odometry.cpp.o.provides + +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o.provides.build: src/CMakeFiles/myslam.dir/visual_odometry.cpp.o + +# Object files for target myslam +myslam_OBJECTS = \ +"CMakeFiles/myslam.dir/frame.cpp.o" \ +"CMakeFiles/myslam.dir/mappoint.cpp.o" \ +"CMakeFiles/myslam.dir/map.cpp.o" \ +"CMakeFiles/myslam.dir/camera.cpp.o" \ +"CMakeFiles/myslam.dir/config.cpp.o" \ +"CMakeFiles/myslam.dir/g2o_types.cpp.o" \ +"CMakeFiles/myslam.dir/visual_odometry.cpp.o" + +# External object files for target myslam +myslam_EXTERNAL_OBJECTS = + +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/frame.cpp.o +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/mappoint.cpp.o +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/map.cpp.o +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/camera.cpp.o +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/config.cpp.o +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/g2o_types.cpp.o +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/visual_odometry.cpp.o +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/build.make +../lib/libmyslam.so: /usr/local/lib/libopencv_viz.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_videostab.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_videoio.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_video.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_superres.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_stitching.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_shape.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_photo.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_objdetect.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_ml.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_imgproc.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_imgcodecs.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_highgui.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_flann.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_features2d.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_core.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_calib3d.so.3.1.0 +../lib/libmyslam.so: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build/libSophus.so +../lib/libmyslam.so: /usr/local/lib/libopencv_features2d.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_ml.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_highgui.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_videoio.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_imgcodecs.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_flann.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_video.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_imgproc.so.3.1.0 +../lib/libmyslam.so: /usr/local/lib/libopencv_core.so.3.1.0 +../lib/libmyslam.so: src/CMakeFiles/myslam.dir/link.txt + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --red --bold "Linking CXX shared library ../../lib/libmyslam.so" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src" && $(CMAKE_COMMAND) -E cmake_link_script CMakeFiles/myslam.dir/link.txt --verbose=$(VERBOSE) + +# Rule to build all files generated by this target. +src/CMakeFiles/myslam.dir/build: ../lib/libmyslam.so +.PHONY : src/CMakeFiles/myslam.dir/build + +src/CMakeFiles/myslam.dir/requires: src/CMakeFiles/myslam.dir/frame.cpp.o.requires +src/CMakeFiles/myslam.dir/requires: src/CMakeFiles/myslam.dir/mappoint.cpp.o.requires +src/CMakeFiles/myslam.dir/requires: src/CMakeFiles/myslam.dir/map.cpp.o.requires +src/CMakeFiles/myslam.dir/requires: src/CMakeFiles/myslam.dir/camera.cpp.o.requires +src/CMakeFiles/myslam.dir/requires: src/CMakeFiles/myslam.dir/config.cpp.o.requires +src/CMakeFiles/myslam.dir/requires: src/CMakeFiles/myslam.dir/g2o_types.cpp.o.requires +src/CMakeFiles/myslam.dir/requires: src/CMakeFiles/myslam.dir/visual_odometry.cpp.o.requires +.PHONY : src/CMakeFiles/myslam.dir/requires + +src/CMakeFiles/myslam.dir/clean: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src" && $(CMAKE_COMMAND) -P CMakeFiles/myslam.dir/cmake_clean.cmake +.PHONY : src/CMakeFiles/myslam.dir/clean + +src/CMakeFiles/myslam.dir/depend: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/DependInfo.cmake" --color=$(COLOR) +.PHONY : src/CMakeFiles/myslam.dir/depend + diff --git a/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/camera.cpp.o b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/camera.cpp.o new file mode 100644 index 00000000..844b6ddf Binary files /dev/null and b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/camera.cpp.o differ diff --git a/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/cmake_clean.cmake b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/cmake_clean.cmake new file mode 100644 index 00000000..c3927b8a --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/cmake_clean.cmake @@ -0,0 +1,16 @@ +FILE(REMOVE_RECURSE + "CMakeFiles/myslam.dir/frame.cpp.o" + "CMakeFiles/myslam.dir/mappoint.cpp.o" + "CMakeFiles/myslam.dir/map.cpp.o" + "CMakeFiles/myslam.dir/camera.cpp.o" + "CMakeFiles/myslam.dir/config.cpp.o" + "CMakeFiles/myslam.dir/g2o_types.cpp.o" + "CMakeFiles/myslam.dir/visual_odometry.cpp.o" + "../../lib/libmyslam.pdb" + "../../lib/libmyslam.so" +) + +# Per-language clean rules from dependency scanning. +FOREACH(lang CXX) + INCLUDE(CMakeFiles/myslam.dir/cmake_clean_${lang}.cmake OPTIONAL) +ENDFOREACH(lang) diff --git a/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/config.cpp.o b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/config.cpp.o new file mode 100644 index 00000000..efc49619 Binary files /dev/null and b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/config.cpp.o differ diff --git a/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/depend.internal b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/depend.internal new file mode 100644 index 00000000..baff7ae2 --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/depend.internal @@ -0,0 +1,1957 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +src/CMakeFiles/myslam.dir/camera.cpp.o + ../include/myslam/camera.h + ../include/myslam/common_include.h + ../include/myslam/config.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/camera.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h +src/CMakeFiles/myslam.dir/config.cpp.o + ../include/myslam/common_include.h + ../include/myslam/config.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/config.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o + ../include/myslam/camera.h + ../include/myslam/common_include.h + ../include/myslam/frame.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/frame.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o + ../include/myslam/camera.h + ../include/myslam/common_include.h + ../include/myslam/g2o_types.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/g2o_types.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Dense + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/g2o/config.h + /usr/local/include/g2o/core/base_binary_edge.h + /usr/local/include/g2o/core/base_binary_edge.hpp + /usr/local/include/g2o/core/base_edge.h + /usr/local/include/g2o/core/base_multi_edge.h + /usr/local/include/g2o/core/base_multi_edge.hpp + /usr/local/include/g2o/core/base_unary_edge.h + /usr/local/include/g2o/core/base_unary_edge.hpp + /usr/local/include/g2o/core/base_vertex.h + /usr/local/include/g2o/core/base_vertex.hpp + /usr/local/include/g2o/core/batch_stats.h + /usr/local/include/g2o/core/block_solver.h + /usr/local/include/g2o/core/block_solver.hpp + /usr/local/include/g2o/core/creators.h + /usr/local/include/g2o/core/eigen_types.h + /usr/local/include/g2o/core/g2o_core_api.h + /usr/local/include/g2o/core/hyper_graph.h + /usr/local/include/g2o/core/jacobian_workspace.h + /usr/local/include/g2o/core/linear_solver.h + /usr/local/include/g2o/core/matrix_operations.h + /usr/local/include/g2o/core/matrix_structure.h + /usr/local/include/g2o/core/openmp_mutex.h + /usr/local/include/g2o/core/optimizable_graph.h + /usr/local/include/g2o/core/optimization_algorithm.h + /usr/local/include/g2o/core/optimization_algorithm_levenberg.h + /usr/local/include/g2o/core/optimization_algorithm_with_hessian.h + /usr/local/include/g2o/core/parameter.h + /usr/local/include/g2o/core/parameter_container.h + /usr/local/include/g2o/core/robust_kernel.h + /usr/local/include/g2o/core/robust_kernel_impl.h + /usr/local/include/g2o/core/solver.h + /usr/local/include/g2o/core/sparse_block_matrix.h + /usr/local/include/g2o/core/sparse_block_matrix.hpp + /usr/local/include/g2o/core/sparse_block_matrix_ccs.h + /usr/local/include/g2o/core/sparse_block_matrix_diagonal.h + /usr/local/include/g2o/core/sparse_optimizer.h + /usr/local/include/g2o/solvers/dense/linear_solver_dense.h + /usr/local/include/g2o/stuff/g2o_stuff_api.h + /usr/local/include/g2o/stuff/macros.h + /usr/local/include/g2o/stuff/misc.h + /usr/local/include/g2o/stuff/property.h + /usr/local/include/g2o/stuff/string_tools.h + /usr/local/include/g2o/stuff/timeutil.h + /usr/local/include/g2o/types/sba/g2o_types_sba_api.h + /usr/local/include/g2o/types/sba/sbacam.h + /usr/local/include/g2o/types/sba/types_sba.h + /usr/local/include/g2o/types/sba/types_six_dof_expmap.h + /usr/local/include/g2o/types/slam3d/g2o_types_slam3d_api.h + /usr/local/include/g2o/types/slam3d/se3_ops.h + /usr/local/include/g2o/types/slam3d/se3_ops.hpp + /usr/local/include/g2o/types/slam3d/se3quat.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h +src/CMakeFiles/myslam.dir/map.cpp.o + ../include/myslam/camera.h + ../include/myslam/common_include.h + ../include/myslam/frame.h + ../include/myslam/map.h + ../include/myslam/mappoint.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/map.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o + ../include/myslam/common_include.h + ../include/myslam/mappoint.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/mappoint.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o + ../include/myslam/camera.h + ../include/myslam/common_include.h + ../include/myslam/config.h + ../include/myslam/frame.h + ../include/myslam/g2o_types.h + ../include/myslam/map.h + ../include/myslam/mappoint.h + ../include/myslam/visual_odometry.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src/visual_odometry.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Dense + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/g2o/config.h + /usr/local/include/g2o/core/base_binary_edge.h + /usr/local/include/g2o/core/base_binary_edge.hpp + /usr/local/include/g2o/core/base_edge.h + /usr/local/include/g2o/core/base_multi_edge.h + /usr/local/include/g2o/core/base_multi_edge.hpp + /usr/local/include/g2o/core/base_unary_edge.h + /usr/local/include/g2o/core/base_unary_edge.hpp + /usr/local/include/g2o/core/base_vertex.h + /usr/local/include/g2o/core/base_vertex.hpp + /usr/local/include/g2o/core/batch_stats.h + /usr/local/include/g2o/core/block_solver.h + /usr/local/include/g2o/core/block_solver.hpp + /usr/local/include/g2o/core/creators.h + /usr/local/include/g2o/core/eigen_types.h + /usr/local/include/g2o/core/g2o_core_api.h + /usr/local/include/g2o/core/hyper_graph.h + /usr/local/include/g2o/core/jacobian_workspace.h + /usr/local/include/g2o/core/linear_solver.h + /usr/local/include/g2o/core/matrix_operations.h + /usr/local/include/g2o/core/matrix_structure.h + /usr/local/include/g2o/core/openmp_mutex.h + /usr/local/include/g2o/core/optimizable_graph.h + /usr/local/include/g2o/core/optimization_algorithm.h + /usr/local/include/g2o/core/optimization_algorithm_levenberg.h + /usr/local/include/g2o/core/optimization_algorithm_with_hessian.h + /usr/local/include/g2o/core/parameter.h + /usr/local/include/g2o/core/parameter_container.h + /usr/local/include/g2o/core/robust_kernel.h + /usr/local/include/g2o/core/robust_kernel_impl.h + /usr/local/include/g2o/core/solver.h + /usr/local/include/g2o/core/sparse_block_matrix.h + /usr/local/include/g2o/core/sparse_block_matrix.hpp + /usr/local/include/g2o/core/sparse_block_matrix_ccs.h + /usr/local/include/g2o/core/sparse_block_matrix_diagonal.h + /usr/local/include/g2o/core/sparse_optimizer.h + /usr/local/include/g2o/solvers/dense/linear_solver_dense.h + /usr/local/include/g2o/stuff/g2o_stuff_api.h + /usr/local/include/g2o/stuff/macros.h + /usr/local/include/g2o/stuff/misc.h + /usr/local/include/g2o/stuff/property.h + /usr/local/include/g2o/stuff/string_tools.h + /usr/local/include/g2o/stuff/timeutil.h + /usr/local/include/g2o/types/sba/g2o_types_sba_api.h + /usr/local/include/g2o/types/sba/sbacam.h + /usr/local/include/g2o/types/sba/types_sba.h + /usr/local/include/g2o/types/sba/types_six_dof_expmap.h + /usr/local/include/g2o/types/slam3d/g2o_types_slam3d_api.h + /usr/local/include/g2o/types/slam3d/se3_ops.h + /usr/local/include/g2o/types/slam3d/se3_ops.hpp + /usr/local/include/g2o/types/slam3d/se3quat.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/features2d/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h diff --git a/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/depend.make b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/depend.make new file mode 100644 index 00000000..51ee5172 --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/depend.make @@ -0,0 +1,1957 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +src/CMakeFiles/myslam.dir/camera.cpp.o: ../include/myslam/camera.h +src/CMakeFiles/myslam.dir/camera.cpp.o: ../include/myslam/common_include.h +src/CMakeFiles/myslam.dir/camera.cpp.o: ../include/myslam/config.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +src/CMakeFiles/myslam.dir/camera.cpp.o: ../src/camera.cpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Cholesky +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Core +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Geometry +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Householder +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/Jacobi +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/LU +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/QR +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/SVD +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/StdVector +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv/cxcore.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/calib3d.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/affine.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/base.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/core.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/core_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/cvdef.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/mat.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/matx.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/operations.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/optim.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/traits.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/types.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/types_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/utility.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/core/version.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/features2d.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/flann/config.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/flann/defines.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/highgui.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/imgproc.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/ml.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/objdetect.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/opencv.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/photo.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/video.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/videoio.hpp +src/CMakeFiles/myslam.dir/camera.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + +src/CMakeFiles/myslam.dir/config.cpp.o: ../include/myslam/common_include.h +src/CMakeFiles/myslam.dir/config.cpp.o: ../include/myslam/config.h +src/CMakeFiles/myslam.dir/config.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +src/CMakeFiles/myslam.dir/config.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +src/CMakeFiles/myslam.dir/config.cpp.o: ../src/config.cpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Cholesky +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Core +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Geometry +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Householder +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/Jacobi +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/LU +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/QR +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/SVD +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/StdVector +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv/cxcore.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/calib3d.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/affine.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/base.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/core.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/core_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/cvdef.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/mat.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/matx.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/operations.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/optim.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/traits.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/types.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/types_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/utility.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/core/version.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/features2d.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/flann/config.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/flann/defines.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/highgui.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/imgproc.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/ml.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/objdetect.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/opencv.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/photo.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/video.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/videoio.hpp +src/CMakeFiles/myslam.dir/config.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + +src/CMakeFiles/myslam.dir/frame.cpp.o: ../include/myslam/camera.h +src/CMakeFiles/myslam.dir/frame.cpp.o: ../include/myslam/common_include.h +src/CMakeFiles/myslam.dir/frame.cpp.o: ../include/myslam/frame.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +src/CMakeFiles/myslam.dir/frame.cpp.o: ../src/frame.cpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Cholesky +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Core +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Geometry +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Householder +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/Jacobi +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/LU +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/QR +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/SVD +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/StdVector +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv/cxcore.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/calib3d.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/affine.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/base.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/core.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/core_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/cvdef.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/mat.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/matx.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/operations.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/optim.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/traits.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/types.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/types_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/utility.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/core/version.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/features2d.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/flann/config.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/flann/defines.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/highgui.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/imgproc.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/ml.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/objdetect.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/opencv.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/photo.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/video.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/videoio.hpp +src/CMakeFiles/myslam.dir/frame.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: ../include/myslam/camera.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: ../include/myslam/common_include.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: ../include/myslam/g2o_types.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: ../src/g2o_types.cpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/Cholesky +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/Core +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/Dense +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/Geometry +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/Householder +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/Jacobi +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/LU +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/QR +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/SVD +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/StdVector +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/config.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/base_binary_edge.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/base_binary_edge.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/base_edge.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/base_multi_edge.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/base_multi_edge.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/base_unary_edge.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/base_unary_edge.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/base_vertex.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/base_vertex.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/batch_stats.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/block_solver.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/block_solver.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/creators.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/eigen_types.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/g2o_core_api.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/hyper_graph.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/jacobian_workspace.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/linear_solver.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/matrix_operations.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/matrix_structure.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/openmp_mutex.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/optimizable_graph.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/optimization_algorithm.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/optimization_algorithm_levenberg.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/optimization_algorithm_with_hessian.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/parameter.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/parameter_container.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/robust_kernel.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/robust_kernel_impl.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/solver.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/sparse_block_matrix.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/sparse_block_matrix.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/sparse_block_matrix_ccs.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/sparse_block_matrix_diagonal.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/core/sparse_optimizer.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/solvers/dense/linear_solver_dense.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/stuff/g2o_stuff_api.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/stuff/macros.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/stuff/misc.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/stuff/property.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/stuff/string_tools.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/stuff/timeutil.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/types/sba/g2o_types_sba_api.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/types/sba/sbacam.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/types/sba/types_sba.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/types/sba/types_six_dof_expmap.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/types/slam3d/g2o_types_slam3d_api.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/types/slam3d/se3_ops.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/types/slam3d/se3_ops.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/g2o/types/slam3d/se3quat.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv/cxcore.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/calib3d.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/affine.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/base.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/core.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/core_c.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/cvdef.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/mat.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/matx.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/operations.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/optim.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/traits.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/types.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/types_c.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/utility.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/core/version.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/features2d.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/flann/config.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/flann/defines.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/highgui.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/imgproc.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/ml.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/objdetect.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/opencv.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/photo.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/video.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/videoio.hpp +src/CMakeFiles/myslam.dir/g2o_types.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + +src/CMakeFiles/myslam.dir/map.cpp.o: ../include/myslam/camera.h +src/CMakeFiles/myslam.dir/map.cpp.o: ../include/myslam/common_include.h +src/CMakeFiles/myslam.dir/map.cpp.o: ../include/myslam/frame.h +src/CMakeFiles/myslam.dir/map.cpp.o: ../include/myslam/map.h +src/CMakeFiles/myslam.dir/map.cpp.o: ../include/myslam/mappoint.h +src/CMakeFiles/myslam.dir/map.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +src/CMakeFiles/myslam.dir/map.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +src/CMakeFiles/myslam.dir/map.cpp.o: ../src/map.cpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Cholesky +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Core +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Geometry +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Householder +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/Jacobi +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/LU +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/QR +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/SVD +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/StdVector +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv/cxcore.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/calib3d.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/affine.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/base.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/core.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/core_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/cvdef.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/mat.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/matx.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/operations.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/optim.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/traits.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/types.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/types_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/utility.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/core/version.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/features2d.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/flann/config.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/flann/defines.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/highgui.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/imgproc.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/ml.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/objdetect.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/opencv.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/photo.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/video.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/videoio.hpp +src/CMakeFiles/myslam.dir/map.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + +src/CMakeFiles/myslam.dir/mappoint.cpp.o: ../include/myslam/common_include.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: ../include/myslam/mappoint.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: ../src/mappoint.cpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Cholesky +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Core +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Geometry +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Householder +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/Jacobi +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/LU +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/QR +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/SVD +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/StdVector +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv/cxcore.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/calib3d.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/affine.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/base.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/core.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/core_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/cvdef.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/mat.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/matx.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/operations.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/optim.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/traits.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/types.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/types_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/utility.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/core/version.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/features2d.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/flann/config.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/flann/defines.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/highgui.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/imgproc.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/ml.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/objdetect.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/opencv.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/photo.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/video.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/videoio.hpp +src/CMakeFiles/myslam.dir/mappoint.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../include/myslam/camera.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../include/myslam/common_include.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../include/myslam/config.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../include/myslam/frame.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../include/myslam/g2o_types.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../include/myslam/map.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../include/myslam/mappoint.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../include/myslam/visual_odometry.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: ../src/visual_odometry.cpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/Cholesky +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/Core +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/Dense +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/Geometry +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/Householder +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/Jacobi +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/LU +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/QR +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/SVD +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/StdVector +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/config.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/base_binary_edge.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/base_binary_edge.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/base_edge.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/base_multi_edge.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/base_multi_edge.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/base_unary_edge.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/base_unary_edge.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/base_vertex.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/base_vertex.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/batch_stats.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/block_solver.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/block_solver.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/creators.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/eigen_types.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/g2o_core_api.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/hyper_graph.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/jacobian_workspace.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/linear_solver.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/matrix_operations.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/matrix_structure.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/openmp_mutex.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/optimizable_graph.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/optimization_algorithm.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/optimization_algorithm_levenberg.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/optimization_algorithm_with_hessian.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/parameter.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/parameter_container.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/robust_kernel.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/robust_kernel_impl.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/solver.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/sparse_block_matrix.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/sparse_block_matrix.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/sparse_block_matrix_ccs.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/sparse_block_matrix_diagonal.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/core/sparse_optimizer.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/solvers/dense/linear_solver_dense.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/stuff/g2o_stuff_api.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/stuff/macros.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/stuff/misc.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/stuff/property.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/stuff/string_tools.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/stuff/timeutil.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/types/sba/g2o_types_sba_api.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/types/sba/sbacam.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/types/sba/types_sba.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/types/sba/types_six_dof_expmap.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/types/slam3d/g2o_types_slam3d_api.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/types/slam3d/se3_ops.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/types/slam3d/se3_ops.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/g2o/types/slam3d/se3quat.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv/cxcore.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/calib3d.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/calib3d/calib3d.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/affine.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/base.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/core.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/core_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/cvdef.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/mat.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/matx.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/operations.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/optim.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/traits.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/types.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/types_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/utility.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/core/version.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/features2d.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/features2d/features2d.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/flann/config.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/flann/defines.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/highgui.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/highgui/highgui.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/imgproc.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/imgproc/imgproc.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/ml.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/objdetect.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/opencv.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/photo.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/video.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/videoio.hpp +src/CMakeFiles/myslam.dir/visual_odometry.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h + diff --git a/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/flags.make b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/flags.make new file mode 100644 index 00000000..deb55edc --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/flags.make @@ -0,0 +1,8 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# compile CXX with g++ +CXX_FLAGS = -std=c++11 -march=native -O3 -O3 -DNDEBUG -fPIC -I/usr/include/eigen3 -I/usr/local/include/opencv -I/usr/local/include -I/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus -I"/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/include" + +CXX_DEFINES = -Dmyslam_EXPORTS + diff --git a/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/frame.cpp.o b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/frame.cpp.o new file mode 100644 index 00000000..63e3fecb Binary files /dev/null and b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/frame.cpp.o differ diff --git a/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/g2o_types.cpp.o b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/g2o_types.cpp.o new file mode 100644 index 00000000..e9724d79 Binary files /dev/null and b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/g2o_types.cpp.o differ diff --git a/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/link.txt b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/link.txt new file mode 100644 index 00000000..e297419d --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/link.txt @@ -0,0 +1 @@ +g++ -fPIC -std=c++11 -march=native -O3 -O3 -DNDEBUG -shared -Wl,-soname,libmyslam.so -o ../../lib/libmyslam.so CMakeFiles/myslam.dir/frame.cpp.o CMakeFiles/myslam.dir/mappoint.cpp.o CMakeFiles/myslam.dir/map.cpp.o CMakeFiles/myslam.dir/camera.cpp.o CMakeFiles/myslam.dir/config.cpp.o CMakeFiles/myslam.dir/g2o_types.cpp.o CMakeFiles/myslam.dir/visual_odometry.cpp.o /usr/local/lib/libopencv_viz.so.3.1.0 /usr/local/lib/libopencv_videostab.so.3.1.0 /usr/local/lib/libopencv_videoio.so.3.1.0 /usr/local/lib/libopencv_video.so.3.1.0 /usr/local/lib/libopencv_superres.so.3.1.0 /usr/local/lib/libopencv_stitching.so.3.1.0 /usr/local/lib/libopencv_shape.so.3.1.0 /usr/local/lib/libopencv_photo.so.3.1.0 /usr/local/lib/libopencv_objdetect.so.3.1.0 /usr/local/lib/libopencv_ml.so.3.1.0 /usr/local/lib/libopencv_imgproc.so.3.1.0 /usr/local/lib/libopencv_imgcodecs.so.3.1.0 /usr/local/lib/libopencv_highgui.so.3.1.0 /usr/local/lib/libopencv_flann.so.3.1.0 /usr/local/lib/libopencv_features2d.so.3.1.0 /usr/local/lib/libopencv_core.so.3.1.0 /usr/local/lib/libopencv_calib3d.so.3.1.0 /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build/libSophus.so -lg2o_core -lg2o_stuff -lg2o_types_sba /usr/local/lib/libopencv_features2d.so.3.1.0 /usr/local/lib/libopencv_ml.so.3.1.0 /usr/local/lib/libopencv_highgui.so.3.1.0 /usr/local/lib/libopencv_videoio.so.3.1.0 /usr/local/lib/libopencv_imgcodecs.so.3.1.0 /usr/local/lib/libopencv_flann.so.3.1.0 /usr/local/lib/libopencv_video.so.3.1.0 /usr/local/lib/libopencv_imgproc.so.3.1.0 /usr/local/lib/libopencv_core.so.3.1.0 -Wl,-rpath,/usr/local/lib:/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build diff --git a/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/map.cpp.o b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/map.cpp.o new file mode 100644 index 00000000..c19116e7 Binary files /dev/null and b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/map.cpp.o differ diff --git a/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/mappoint.cpp.o b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/mappoint.cpp.o new file mode 100644 index 00000000..29cf3d00 Binary files /dev/null and b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/mappoint.cpp.o differ diff --git a/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/progress.make b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/progress.make new file mode 100644 index 00000000..2f823159 --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/progress.make @@ -0,0 +1,8 @@ +CMAKE_PROGRESS_1 = 1 +CMAKE_PROGRESS_2 = 2 +CMAKE_PROGRESS_3 = 3 +CMAKE_PROGRESS_4 = 4 +CMAKE_PROGRESS_5 = 5 +CMAKE_PROGRESS_6 = 6 +CMAKE_PROGRESS_7 = 7 + diff --git a/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/visual_odometry.cpp.o b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/visual_odometry.cpp.o new file mode 100644 index 00000000..91aa2055 Binary files /dev/null and b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/visual_odometry.cpp.o differ diff --git a/vSLAM/ch9 project/0.4/build/src/CMakeFiles/progress.marks b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/progress.marks new file mode 100644 index 00000000..7f8f011e --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/src/CMakeFiles/progress.marks @@ -0,0 +1 @@ +7 diff --git a/vSLAM/ch9 project/0.4/build/src/Makefile b/vSLAM/ch9 project/0.4/build/src/Makefile new file mode 100644 index 00000000..33162c95 --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/src/Makefile @@ -0,0 +1,326 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Default target executed when no arguments are given to make. +default_target: all +.PHONY : default_target + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4" + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" + +#============================================================================= +# Targets provided globally by CMake. + +# Special rule for the target edit_cache +edit_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running interactive CMake command-line interface..." + /usr/bin/cmake -i . +.PHONY : edit_cache + +# Special rule for the target edit_cache +edit_cache/fast: edit_cache +.PHONY : edit_cache/fast + +# Special rule for the target rebuild_cache +rebuild_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake to regenerate build system..." + /usr/bin/cmake -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) +.PHONY : rebuild_cache + +# Special rule for the target rebuild_cache +rebuild_cache/fast: rebuild_cache +.PHONY : rebuild_cache/fast + +# The main all target +all: cmake_check_build_system + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src/CMakeFiles/progress.marks" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f CMakeFiles/Makefile2 src/all + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles" 0 +.PHONY : all + +# The main clean target +clean: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f CMakeFiles/Makefile2 src/clean +.PHONY : clean + +# The main clean target +clean/fast: clean +.PHONY : clean/fast + +# Prepare targets for installation. +preinstall: all + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f CMakeFiles/Makefile2 src/preinstall +.PHONY : preinstall + +# Prepare targets for installation. +preinstall/fast: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f CMakeFiles/Makefile2 src/preinstall +.PHONY : preinstall/fast + +# clear depends +depend: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 1 +.PHONY : depend + +# Convenience name for target. +src/CMakeFiles/myslam.dir/rule: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f CMakeFiles/Makefile2 src/CMakeFiles/myslam.dir/rule +.PHONY : src/CMakeFiles/myslam.dir/rule + +# Convenience name for target. +myslam: src/CMakeFiles/myslam.dir/rule +.PHONY : myslam + +# fast build rule for target. +myslam/fast: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/build +.PHONY : myslam/fast + +camera.o: camera.cpp.o +.PHONY : camera.o + +# target to build an object file +camera.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/camera.cpp.o +.PHONY : camera.cpp.o + +camera.i: camera.cpp.i +.PHONY : camera.i + +# target to preprocess a source file +camera.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/camera.cpp.i +.PHONY : camera.cpp.i + +camera.s: camera.cpp.s +.PHONY : camera.s + +# target to generate assembly for a file +camera.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/camera.cpp.s +.PHONY : camera.cpp.s + +config.o: config.cpp.o +.PHONY : config.o + +# target to build an object file +config.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/config.cpp.o +.PHONY : config.cpp.o + +config.i: config.cpp.i +.PHONY : config.i + +# target to preprocess a source file +config.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/config.cpp.i +.PHONY : config.cpp.i + +config.s: config.cpp.s +.PHONY : config.s + +# target to generate assembly for a file +config.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/config.cpp.s +.PHONY : config.cpp.s + +frame.o: frame.cpp.o +.PHONY : frame.o + +# target to build an object file +frame.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/frame.cpp.o +.PHONY : frame.cpp.o + +frame.i: frame.cpp.i +.PHONY : frame.i + +# target to preprocess a source file +frame.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/frame.cpp.i +.PHONY : frame.cpp.i + +frame.s: frame.cpp.s +.PHONY : frame.s + +# target to generate assembly for a file +frame.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/frame.cpp.s +.PHONY : frame.cpp.s + +g2o_types.o: g2o_types.cpp.o +.PHONY : g2o_types.o + +# target to build an object file +g2o_types.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/g2o_types.cpp.o +.PHONY : g2o_types.cpp.o + +g2o_types.i: g2o_types.cpp.i +.PHONY : g2o_types.i + +# target to preprocess a source file +g2o_types.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/g2o_types.cpp.i +.PHONY : g2o_types.cpp.i + +g2o_types.s: g2o_types.cpp.s +.PHONY : g2o_types.s + +# target to generate assembly for a file +g2o_types.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/g2o_types.cpp.s +.PHONY : g2o_types.cpp.s + +map.o: map.cpp.o +.PHONY : map.o + +# target to build an object file +map.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/map.cpp.o +.PHONY : map.cpp.o + +map.i: map.cpp.i +.PHONY : map.i + +# target to preprocess a source file +map.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/map.cpp.i +.PHONY : map.cpp.i + +map.s: map.cpp.s +.PHONY : map.s + +# target to generate assembly for a file +map.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/map.cpp.s +.PHONY : map.cpp.s + +mappoint.o: mappoint.cpp.o +.PHONY : mappoint.o + +# target to build an object file +mappoint.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/mappoint.cpp.o +.PHONY : mappoint.cpp.o + +mappoint.i: mappoint.cpp.i +.PHONY : mappoint.i + +# target to preprocess a source file +mappoint.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/mappoint.cpp.i +.PHONY : mappoint.cpp.i + +mappoint.s: mappoint.cpp.s +.PHONY : mappoint.s + +# target to generate assembly for a file +mappoint.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/mappoint.cpp.s +.PHONY : mappoint.cpp.s + +visual_odometry.o: visual_odometry.cpp.o +.PHONY : visual_odometry.o + +# target to build an object file +visual_odometry.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/visual_odometry.cpp.o +.PHONY : visual_odometry.cpp.o + +visual_odometry.i: visual_odometry.cpp.i +.PHONY : visual_odometry.i + +# target to preprocess a source file +visual_odometry.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/visual_odometry.cpp.i +.PHONY : visual_odometry.cpp.i + +visual_odometry.s: visual_odometry.cpp.s +.PHONY : visual_odometry.s + +# target to generate assembly for a file +visual_odometry.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f src/CMakeFiles/myslam.dir/build.make src/CMakeFiles/myslam.dir/visual_odometry.cpp.s +.PHONY : visual_odometry.cpp.s + +# Help Target +help: + @echo "The following are some of the valid targets for this Makefile:" + @echo "... all (the default if no target is provided)" + @echo "... clean" + @echo "... depend" + @echo "... edit_cache" + @echo "... myslam" + @echo "... rebuild_cache" + @echo "... camera.o" + @echo "... camera.i" + @echo "... camera.s" + @echo "... config.o" + @echo "... config.i" + @echo "... config.s" + @echo "... frame.o" + @echo "... frame.i" + @echo "... frame.s" + @echo "... g2o_types.o" + @echo "... g2o_types.i" + @echo "... g2o_types.s" + @echo "... map.o" + @echo "... map.i" + @echo "... map.s" + @echo "... mappoint.o" + @echo "... mappoint.i" + @echo "... mappoint.s" + @echo "... visual_odometry.o" + @echo "... visual_odometry.i" + @echo "... visual_odometry.s" +.PHONY : help + + + +#============================================================================= +# Special targets to cleanup operation of make. + +# Special rule to run CMake to check the build system integrity. +# No rule that depends on this can have commands that come from listfiles +# because they might be regenerated. +cmake_check_build_system: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0 +.PHONY : cmake_check_build_system + diff --git a/vSLAM/ch9 project/0.4/build/src/cmake_install.cmake b/vSLAM/ch9 project/0.4/build/src/cmake_install.cmake new file mode 100644 index 00000000..5299e1f8 --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/src/cmake_install.cmake @@ -0,0 +1,34 @@ +# Install script for directory: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/src + +# Set the install prefix +IF(NOT DEFINED CMAKE_INSTALL_PREFIX) + SET(CMAKE_INSTALL_PREFIX "/usr/local") +ENDIF(NOT DEFINED CMAKE_INSTALL_PREFIX) +STRING(REGEX REPLACE "/$" "" CMAKE_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}") + +# Set the install configuration name. +IF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + IF(BUILD_TYPE) + STRING(REGEX REPLACE "^[^A-Za-z0-9_]+" "" + CMAKE_INSTALL_CONFIG_NAME "${BUILD_TYPE}") + ELSE(BUILD_TYPE) + SET(CMAKE_INSTALL_CONFIG_NAME "Release") + ENDIF(BUILD_TYPE) + MESSAGE(STATUS "Install configuration: \"${CMAKE_INSTALL_CONFIG_NAME}\"") +ENDIF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + +# Set the component getting installed. +IF(NOT CMAKE_INSTALL_COMPONENT) + IF(COMPONENT) + MESSAGE(STATUS "Install component: \"${COMPONENT}\"") + SET(CMAKE_INSTALL_COMPONENT "${COMPONENT}") + ELSE(COMPONENT) + SET(CMAKE_INSTALL_COMPONENT) + ENDIF(COMPONENT) +ENDIF(NOT CMAKE_INSTALL_COMPONENT) + +# Install shared libraries without execute permission? +IF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + SET(CMAKE_INSTALL_SO_NO_EXE "1") +ENDIF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + diff --git a/vSLAM/ch9 project/0.4/build/test/CMakeFiles/CMakeDirectoryInformation.cmake b/vSLAM/ch9 project/0.4/build/test/CMakeFiles/CMakeDirectoryInformation.cmake new file mode 100644 index 00000000..debec154 --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/test/CMakeFiles/CMakeDirectoryInformation.cmake @@ -0,0 +1,16 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Relative path conversion top directories. +SET(CMAKE_RELATIVE_PATH_TOP_SOURCE "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4") +SET(CMAKE_RELATIVE_PATH_TOP_BINARY "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build") + +# Force unix paths in dependencies. +SET(CMAKE_FORCE_UNIX_PATHS 1) + + +# The C and CXX include file regular expressions for this directory. +SET(CMAKE_C_INCLUDE_REGEX_SCAN "^.*$") +SET(CMAKE_C_INCLUDE_REGEX_COMPLAIN "^$") +SET(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN}) +SET(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN}) diff --git a/vSLAM/ch9 project/0.4/build/test/CMakeFiles/progress.marks b/vSLAM/ch9 project/0.4/build/test/CMakeFiles/progress.marks new file mode 100644 index 00000000..45a4fb75 --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/test/CMakeFiles/progress.marks @@ -0,0 +1 @@ +8 diff --git a/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/CXX.includecache b/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/CXX.includecache new file mode 100644 index 00000000..292afc6f --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/CXX.includecache @@ -0,0 +1,1608 @@ +#IncludeRegexLine: ^[ ]*#[ ]*(include|import)[ ]*[<"]([^">]+)([">]) + +#IncludeRegexScan: ^.*$ + +#IncludeRegexComplain: ^$ + +#IncludeRegexTransform: + +../include/myslam/camera.h +myslam/common_include.h +../include/myslam/myslam/common_include.h + +../include/myslam/common_include.h +Eigen/Core +- +Eigen/Geometry +- +sophus/se3.h +- +sophus/so3.h +- +opencv2/core/core.hpp +- +vector +- +list +- +memory +- +string +- +iostream +- +set +- +unordered_map +- +map +- + +../include/myslam/config.h +myslam/common_include.h +../include/myslam/myslam/common_include.h + +../include/myslam/frame.h +myslam/common_include.h +../include/myslam/myslam/common_include.h +myslam/camera.h +../include/myslam/myslam/camera.h + +../include/myslam/map.h +myslam/common_include.h +../include/myslam/myslam/common_include.h +myslam/frame.h +../include/myslam/myslam/frame.h +myslam/mappoint.h +../include/myslam/myslam/mappoint.h + +../include/myslam/mappoint.h +myslam/common_include.h +../include/myslam/myslam/common_include.h + +../include/myslam/visual_odometry.h +myslam/common_include.h +../include/myslam/myslam/common_include.h +myslam/map.h +../include/myslam/myslam/map.h +opencv2/features2d/features2d.hpp +- + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +so3.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +Eigen/Core +- +Eigen/StdVector +- +Eigen/Geometry +- + +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/test/run_vo.cpp +fstream +- +boost/timer.hpp +- +opencv2/imgcodecs.hpp +- +opencv2/highgui/highgui.hpp +- +opencv2/viz.hpp +- +opencv2/imgproc/imgproc.hpp +- +myslam/config.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/test/myslam/config.h +myslam/visual_odometry.h +/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/test/myslam/visual_odometry.h + +/usr/include/eigen3/Eigen/Cholesky +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/Cholesky/LLT.h +/usr/include/eigen3/Eigen/src/Cholesky/LLT.h +src/Cholesky/LDLT.h +/usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +src/Cholesky/LLT_MKL.h +/usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Core/util/Macros.h +/usr/include/eigen3/Eigen/src/Core/util/Macros.h +complex +- +src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +malloc.h +- +immintrin.h +- +emmintrin.h +- +xmmintrin.h +- +pmmintrin.h +- +tmmintrin.h +- +smmintrin.h +- +nmmintrin.h +- +altivec.h +- +arm_neon.h +- +omp.h +- +cerrno +- +cstddef +- +cstdlib +- +cmath +- +cassert +- +functional +- +iosfwd +- +cstring +- +string +- +limits +- +climits +- +algorithm +- +iostream +- +intrin.h +- +new +- +src/Core/util/Constants.h +/usr/include/eigen3/Eigen/src/Core/util/Constants.h +src/Core/util/ForwardDeclarations.h +/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +src/Core/util/Meta.h +/usr/include/eigen3/Eigen/src/Core/util/Meta.h +src/Core/util/StaticAssert.h +/usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +src/Core/util/XprHelper.h +/usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +src/Core/util/Memory.h +/usr/include/eigen3/Eigen/src/Core/util/Memory.h +src/Core/NumTraits.h +/usr/include/eigen3/Eigen/src/Core/NumTraits.h +src/Core/MathFunctions.h +/usr/include/eigen3/Eigen/src/Core/MathFunctions.h +src/Core/GenericPacketMath.h +/usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +src/Core/arch/SSE/PacketMath.h +/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +src/Core/arch/SSE/MathFunctions.h +/usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +src/Core/arch/SSE/Complex.h +/usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +src/Core/arch/AltiVec/PacketMath.h +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +src/Core/arch/AltiVec/Complex.h +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +src/Core/arch/NEON/PacketMath.h +/usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +src/Core/arch/NEON/Complex.h +/usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +src/Core/arch/Default/Settings.h +/usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +src/Core/Functors.h +/usr/include/eigen3/Eigen/src/Core/Functors.h +src/Core/DenseCoeffsBase.h +/usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +src/Core/DenseBase.h +/usr/include/eigen3/Eigen/src/Core/DenseBase.h +src/Core/MatrixBase.h +/usr/include/eigen3/Eigen/src/Core/MatrixBase.h +src/Core/EigenBase.h +/usr/include/eigen3/Eigen/src/Core/EigenBase.h +src/Core/Assign.h +/usr/include/eigen3/Eigen/src/Core/Assign.h +src/Core/util/BlasUtil.h +/usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +src/Core/DenseStorage.h +/usr/include/eigen3/Eigen/src/Core/DenseStorage.h +src/Core/NestByValue.h +/usr/include/eigen3/Eigen/src/Core/NestByValue.h +src/Core/ForceAlignedAccess.h +/usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +src/Core/ReturnByValue.h +/usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +src/Core/NoAlias.h +/usr/include/eigen3/Eigen/src/Core/NoAlias.h +src/Core/PlainObjectBase.h +/usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +src/Core/Matrix.h +/usr/include/eigen3/Eigen/src/Core/Matrix.h +src/Core/Array.h +/usr/include/eigen3/Eigen/src/Core/Array.h +src/Core/CwiseBinaryOp.h +/usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +src/Core/CwiseUnaryOp.h +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +src/Core/CwiseNullaryOp.h +/usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +src/Core/CwiseUnaryView.h +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +src/Core/SelfCwiseBinaryOp.h +/usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +src/Core/Dot.h +/usr/include/eigen3/Eigen/src/Core/Dot.h +src/Core/StableNorm.h +/usr/include/eigen3/Eigen/src/Core/StableNorm.h +src/Core/MapBase.h +/usr/include/eigen3/Eigen/src/Core/MapBase.h +src/Core/Stride.h +/usr/include/eigen3/Eigen/src/Core/Stride.h +src/Core/Map.h +/usr/include/eigen3/Eigen/src/Core/Map.h +src/Core/Block.h +/usr/include/eigen3/Eigen/src/Core/Block.h +src/Core/VectorBlock.h +/usr/include/eigen3/Eigen/src/Core/VectorBlock.h +src/Core/Ref.h +/usr/include/eigen3/Eigen/src/Core/Ref.h +src/Core/Transpose.h +/usr/include/eigen3/Eigen/src/Core/Transpose.h +src/Core/DiagonalMatrix.h +/usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +src/Core/Diagonal.h +/usr/include/eigen3/Eigen/src/Core/Diagonal.h +src/Core/DiagonalProduct.h +/usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +src/Core/PermutationMatrix.h +/usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +src/Core/Transpositions.h +/usr/include/eigen3/Eigen/src/Core/Transpositions.h +src/Core/Redux.h +/usr/include/eigen3/Eigen/src/Core/Redux.h +src/Core/Visitor.h +/usr/include/eigen3/Eigen/src/Core/Visitor.h +src/Core/Fuzzy.h +/usr/include/eigen3/Eigen/src/Core/Fuzzy.h +src/Core/IO.h +/usr/include/eigen3/Eigen/src/Core/IO.h +src/Core/Swap.h +/usr/include/eigen3/Eigen/src/Core/Swap.h +src/Core/CommaInitializer.h +/usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +src/Core/Flagged.h +/usr/include/eigen3/Eigen/src/Core/Flagged.h +src/Core/ProductBase.h +/usr/include/eigen3/Eigen/src/Core/ProductBase.h +src/Core/GeneralProduct.h +/usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +src/Core/TriangularMatrix.h +/usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +src/Core/SelfAdjointView.h +/usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +src/Core/products/GeneralBlockPanelKernel.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +src/Core/products/Parallelizer.h +/usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +src/Core/products/CoeffBasedProduct.h +/usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +src/Core/products/GeneralMatrixVector.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +src/Core/products/GeneralMatrixMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +src/Core/SolveTriangular.h +/usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +src/Core/products/GeneralMatrixMatrixTriangular.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +src/Core/products/SelfadjointMatrixVector.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +src/Core/products/SelfadjointMatrixMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +src/Core/products/SelfadjointProduct.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +src/Core/products/SelfadjointRank2Update.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +src/Core/products/TriangularMatrixVector.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +src/Core/products/TriangularMatrixMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +src/Core/products/TriangularSolverMatrix.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +src/Core/products/TriangularSolverVector.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +src/Core/BandMatrix.h +/usr/include/eigen3/Eigen/src/Core/BandMatrix.h +src/Core/CoreIterators.h +/usr/include/eigen3/Eigen/src/Core/CoreIterators.h +src/Core/BooleanRedux.h +/usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +src/Core/Select.h +/usr/include/eigen3/Eigen/src/Core/Select.h +src/Core/VectorwiseOp.h +/usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +src/Core/Random.h +/usr/include/eigen3/Eigen/src/Core/Random.h +src/Core/Replicate.h +/usr/include/eigen3/Eigen/src/Core/Replicate.h +src/Core/Reverse.h +/usr/include/eigen3/Eigen/src/Core/Reverse.h +src/Core/ArrayBase.h +/usr/include/eigen3/Eigen/src/Core/ArrayBase.h +src/Core/ArrayWrapper.h +/usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +src/Core/products/GeneralMatrixMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +src/Core/products/GeneralMatrixVector_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +src/Core/products/SelfadjointMatrixMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +src/Core/products/SelfadjointMatrixVector_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +src/Core/products/TriangularMatrixMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +src/Core/products/TriangularMatrixVector_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +src/Core/products/TriangularSolverMatrix_MKL.h +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +src/Core/Assign_MKL.h +/usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +src/Core/GlobalFunctions.h +/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +Eigen2Support +/usr/include/eigen3/Eigen/Eigen2Support + +/usr/include/eigen3/Eigen/Eigen2Support +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Eigen2Support/Macros.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +src/Eigen2Support/Memory.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +src/Eigen2Support/Meta.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +src/Eigen2Support/Lazy.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +src/Eigen2Support/Cwise.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +src/Eigen2Support/CwiseOperators.h +/usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +src/Eigen2Support/TriangularSolver.h +/usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +src/Eigen2Support/Block.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +src/Eigen2Support/VectorBlock.h +/usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +src/Eigen2Support/Minor.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +src/Eigen2Support/MathFunctions.h +/usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +iostream +- + +/usr/include/eigen3/Eigen/Eigenvalues +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +Cholesky +/usr/include/eigen3/Eigen/Cholesky +Jacobi +/usr/include/eigen3/Eigen/Jacobi +Householder +/usr/include/eigen3/Eigen/Householder +LU +/usr/include/eigen3/Eigen/LU +Geometry +/usr/include/eigen3/Eigen/Geometry +src/Eigenvalues/Tridiagonalization.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +src/Eigenvalues/RealSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +src/Eigenvalues/EigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +src/Eigenvalues/SelfAdjointEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +src/Eigenvalues/HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +src/Eigenvalues/ComplexSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +src/Eigenvalues/ComplexEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +src/Eigenvalues/RealQZ.h +/usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +src/Eigenvalues/GeneralizedEigenSolver.h +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +src/Eigenvalues/MatrixBaseEigenvalues.h +/usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +src/Eigenvalues/RealSchur_MKL.h +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +src/Eigenvalues/ComplexSchur_MKL.h +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Geometry +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +SVD +/usr/include/eigen3/Eigen/SVD +LU +/usr/include/eigen3/Eigen/LU +limits +- +src/Geometry/OrthoMethods.h +/usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +src/Geometry/EulerAngles.h +/usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +src/Geometry/Homogeneous.h +/usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +src/Geometry/RotationBase.h +/usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +src/Geometry/Rotation2D.h +/usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +src/Geometry/Quaternion.h +/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +src/Geometry/AngleAxis.h +/usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +src/Geometry/Transform.h +/usr/include/eigen3/Eigen/src/Geometry/Transform.h +src/Geometry/Translation.h +/usr/include/eigen3/Eigen/src/Geometry/Translation.h +src/Geometry/Scaling.h +/usr/include/eigen3/Eigen/src/Geometry/Scaling.h +src/Geometry/Hyperplane.h +/usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +src/Geometry/ParametrizedLine.h +/usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +src/Geometry/AlignedBox.h +/usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +src/Geometry/Umeyama.h +/usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +src/Geometry/arch/Geometry_SSE.h +/usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +src/Eigen2Support/Geometry/All.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Householder +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Householder/Householder.h +/usr/include/eigen3/Eigen/src/Householder/Householder.h +src/Householder/HouseholderSequence.h +/usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +src/Householder/BlockHouseholder.h +/usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/Jacobi +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/Jacobi/Jacobi.h +/usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/LU +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/misc/Kernel.h +/usr/include/eigen3/Eigen/src/misc/Kernel.h +src/misc/Image.h +/usr/include/eigen3/Eigen/src/misc/Image.h +src/LU/FullPivLU.h +/usr/include/eigen3/Eigen/src/LU/FullPivLU.h +src/LU/PartialPivLU.h +/usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +src/LU/PartialPivLU_MKL.h +/usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +src/LU/Determinant.h +/usr/include/eigen3/Eigen/src/LU/Determinant.h +src/LU/Inverse.h +/usr/include/eigen3/Eigen/src/LU/Inverse.h +src/LU/arch/Inverse_SSE.h +/usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +src/Eigen2Support/LU.h +/usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/QR +Core +/usr/include/eigen3/Eigen/Core +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +Cholesky +/usr/include/eigen3/Eigen/Cholesky +Jacobi +/usr/include/eigen3/Eigen/Jacobi +Householder +/usr/include/eigen3/Eigen/Householder +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/QR/HouseholderQR.h +/usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +src/QR/FullPivHouseholderQR.h +/usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +src/QR/ColPivHouseholderQR.h +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +src/QR/HouseholderQR_MKL.h +/usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +src/QR/ColPivHouseholderQR_MKL.h +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +src/Eigen2Support/QR.h +/usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +Eigenvalues +/usr/include/eigen3/Eigen/Eigenvalues + +/usr/include/eigen3/Eigen/SVD +QR +/usr/include/eigen3/Eigen/QR +Householder +/usr/include/eigen3/Eigen/Householder +Jacobi +/usr/include/eigen3/Eigen/Jacobi +src/Core/util/DisableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +src/misc/Solve.h +/usr/include/eigen3/Eigen/src/misc/Solve.h +src/SVD/JacobiSVD.h +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +src/SVD/JacobiSVD_MKL.h +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +src/SVD/UpperBidiagonalization.h +/usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +src/Eigen2Support/SVD.h +/usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +src/Core/util/ReenableStupidWarnings.h +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/StdVector +Core +/usr/include/eigen3/Eigen/Core +vector +- +src/StlSupport/StdVector.h +/usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + +/usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + +/usr/include/eigen3/Eigen/src/Cholesky/LLT.h + +/usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Cholesky/Eigen/src/Core/util/MKL_support.h +iostream +- + +/usr/include/eigen3/Eigen/src/Core/Array.h + +/usr/include/eigen3/Eigen/src/Core/ArrayBase.h +../plugins/CommonCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +../plugins/MatrixCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +../plugins/ArrayCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +../plugins/CommonCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +../plugins/MatrixCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +../plugins/ArrayCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + +/usr/include/eigen3/Eigen/src/Core/Assign.h + +/usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + +/usr/include/eigen3/Eigen/src/Core/BandMatrix.h + +/usr/include/eigen3/Eigen/src/Core/Block.h + +/usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + +/usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + +/usr/include/eigen3/Eigen/src/Core/CoreIterators.h + +/usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + +/usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + +/usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + +/usr/include/eigen3/Eigen/src/Core/DenseBase.h +../plugins/BlockMethods.h +/usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + +/usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + +/usr/include/eigen3/Eigen/src/Core/DenseStorage.h + +/usr/include/eigen3/Eigen/src/Core/Diagonal.h + +/usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + +/usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + +/usr/include/eigen3/Eigen/src/Core/Dot.h + +/usr/include/eigen3/Eigen/src/Core/EigenBase.h + +/usr/include/eigen3/Eigen/src/Core/Flagged.h + +/usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + +/usr/include/eigen3/Eigen/src/Core/Functors.h + +/usr/include/eigen3/Eigen/src/Core/Fuzzy.h + +/usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + +/usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + +/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + +/usr/include/eigen3/Eigen/src/Core/IO.h + +/usr/include/eigen3/Eigen/src/Core/Map.h + +/usr/include/eigen3/Eigen/src/Core/MapBase.h + +/usr/include/eigen3/Eigen/src/Core/MathFunctions.h + +/usr/include/eigen3/Eigen/src/Core/Matrix.h + +/usr/include/eigen3/Eigen/src/Core/MatrixBase.h +../plugins/CommonCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +../plugins/CommonCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +../plugins/MatrixCwiseUnaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +../plugins/MatrixCwiseBinaryOps.h +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/Core/NestByValue.h + +/usr/include/eigen3/Eigen/src/Core/NoAlias.h + +/usr/include/eigen3/Eigen/src/Core/NumTraits.h + +/usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + +/usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + +/usr/include/eigen3/Eigen/src/Core/ProductBase.h + +/usr/include/eigen3/Eigen/src/Core/Random.h + +/usr/include/eigen3/Eigen/src/Core/Redux.h + +/usr/include/eigen3/Eigen/src/Core/Ref.h + +/usr/include/eigen3/Eigen/src/Core/Replicate.h + +/usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + +/usr/include/eigen3/Eigen/src/Core/Reverse.h + +/usr/include/eigen3/Eigen/src/Core/Select.h + +/usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + +/usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + +/usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + +/usr/include/eigen3/Eigen/src/Core/StableNorm.h + +/usr/include/eigen3/Eigen/src/Core/Stride.h + +/usr/include/eigen3/Eigen/src/Core/Swap.h + +/usr/include/eigen3/Eigen/src/Core/Transpose.h + +/usr/include/eigen3/Eigen/src/Core/Transpositions.h + +/usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + +/usr/include/eigen3/Eigen/src/Core/VectorBlock.h + +/usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + +/usr/include/eigen3/Eigen/src/Core/Visitor.h + +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + +/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + +/usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + +/usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + +/usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + +/usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + +/usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + +/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + +/usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + +/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + +/usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + +/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + +/usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + +/usr/include/eigen3/Eigen/src/Core/util/Constants.h + +/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + +/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + +/usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +mkl.h +- +mkl_lapacke.h +- + +/usr/include/eigen3/Eigen/src/Core/util/Macros.h +cstdlib +- +iostream +- + +/usr/include/eigen3/Eigen/src/Core/util/Memory.h +unistd.h +- + +/usr/include/eigen3/Eigen/src/Core/util/Meta.h + +/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + +/usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + +/usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +limits +- +RotationBase.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +Rotation2D.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +Quaternion.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +AngleAxis.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +Transform.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +Translation.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +Scaling.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +AlignedBox.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +Hyperplane.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +ParametrizedLine.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +RotationBase.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +Rotation2D.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +Quaternion.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +AngleAxis.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +Transform.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +Translation.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +Scaling.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +AlignedBox.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +Hyperplane.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +ParametrizedLine.h +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + +/usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/././HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/././HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +./ComplexSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +./RealSchur.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +./RealQZ.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +./Tridiagonalization.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +./HessenbergDecomposition.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +./Tridiagonalization.h +/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + +/usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + +/usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + +/usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + +/usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + +/usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + +/usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + +/usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + +/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + +/usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + +/usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + +/usr/include/eigen3/Eigen/src/Geometry/Scaling.h + +/usr/include/eigen3/Eigen/src/Geometry/Transform.h + +/usr/include/eigen3/Eigen/src/Geometry/Translation.h + +/usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + +/usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + +/usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + +/usr/include/eigen3/Eigen/src/Householder/Householder.h + +/usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + +/usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + +/usr/include/eigen3/Eigen/src/LU/Determinant.h + +/usr/include/eigen3/Eigen/src/LU/FullPivLU.h + +/usr/include/eigen3/Eigen/src/LU/Inverse.h + +/usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + +/usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/LU/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + +/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/QR/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + +/usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + +/usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/QR/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + +/usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +Eigen/src/Core/util/MKL_support.h +/usr/include/eigen3/Eigen/src/SVD/Eigen/src/Core/util/MKL_support.h + +/usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + +/usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +Eigen/src/StlSupport/details.h +/usr/include/eigen3/Eigen/src/StlSupport/Eigen/src/StlSupport/details.h + +/usr/include/eigen3/Eigen/src/StlSupport/details.h + +/usr/include/eigen3/Eigen/src/misc/Image.h + +/usr/include/eigen3/Eigen/src/misc/Kernel.h + +/usr/include/eigen3/Eigen/src/misc/Solve.h + +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + +/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + +/usr/local/include/opencv/cxcore.h +opencv2/core/core_c.h +/usr/local/include/opencv/opencv2/core/core_c.h + +/usr/local/include/opencv2/calib3d.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/opencv2/features2d.hpp +opencv2/core/affine.hpp +/usr/local/include/opencv2/opencv2/core/affine.hpp +opencv2/calib3d/calib3d_c.h +/usr/local/include/opencv2/opencv2/calib3d/calib3d_c.h + +/usr/local/include/opencv2/calib3d/calib3d_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/calib3d/opencv2/core/core_c.h + +/usr/local/include/opencv2/core.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/opencv2/core/cvdef.h +opencv2/core/version.hpp +/usr/local/include/opencv2/opencv2/core/version.hpp +opencv2/core/base.hpp +/usr/local/include/opencv2/opencv2/core/base.hpp +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/opencv2/core/cvstd.hpp +opencv2/core/traits.hpp +/usr/local/include/opencv2/opencv2/core/traits.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/opencv2/core/matx.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/opencv2/core/types.hpp +opencv2/core/mat.hpp +/usr/local/include/opencv2/opencv2/core/mat.hpp +opencv2/core/persistence.hpp +/usr/local/include/opencv2/opencv2/core/persistence.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/opencv2/opencv.hpp +opencv2/xfeatures2d.hpp +/usr/local/include/opencv2/opencv2/xfeatures2d.hpp +opencv2/core/operations.hpp +/usr/local/include/opencv2/opencv2/core/operations.hpp +opencv2/core/cvstd.inl.hpp +/usr/local/include/opencv2/opencv2/core/cvstd.inl.hpp +opencv2/core/utility.hpp +/usr/local/include/opencv2/opencv2/core/utility.hpp +opencv2/core/optim.hpp +/usr/local/include/opencv2/opencv2/core/optim.hpp + +/usr/local/include/opencv2/core/affine.hpp +opencv2/core.hpp +- + +/usr/local/include/opencv2/core/base.hpp +climits +- +algorithm +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/core/opencv2/core/cvstd.hpp +opencv2/core/neon_utils.hpp +/usr/local/include/opencv2/core/opencv2/core/neon_utils.hpp + +/usr/local/include/opencv2/core/bufferpool.hpp + +/usr/local/include/opencv2/core/core.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/core_c.h +opencv2/core/types_c.h +/usr/local/include/opencv2/core/opencv2/core/types_c.h +cxcore.h +/usr/local/include/opencv2/core/cxcore.h +cxcore.h +/usr/local/include/opencv2/core/cxcore.h +opencv2/core/utility.hpp +/usr/local/include/opencv2/core/opencv2/core/utility.hpp + +/usr/local/include/opencv2/core/cvdef.h +limits.h +- +opencv2/core/hal/interface.h +/usr/local/include/opencv2/core/opencv2/core/hal/interface.h +emmintrin.h +- +pmmintrin.h +- +tmmintrin.h +- +smmintrin.h +- +nmmintrin.h +- +nmmintrin.h +- +popcntintrin.h +- +immintrin.h +- +immintrin.h +- +Intrin.h +- +arm_neon.h +/usr/local/include/opencv2/core/arm_neon.h +arm_neon.h +- +intrin.h +- + +/usr/local/include/opencv2/core/cvstd.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +cstddef +- +cstring +- +cctype +- +string +- +algorithm +- +utility +- +cstdlib +- +cmath +- +opencv2/core/ptr.inl.hpp +/usr/local/include/opencv2/core/opencv2/core/ptr.inl.hpp + +/usr/local/include/opencv2/core/cvstd.inl.hpp +complex +- +ostream +- + +/usr/local/include/opencv2/core/fast_math.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +fastmath.h +- +cmath +- +math.h +- +tegra_round.hpp +/usr/local/include/opencv2/core/tegra_round.hpp + +/usr/local/include/opencv2/core/hal/interface.h +cstddef +- +stddef.h +- +cstdint +- +stdint.h +- + +/usr/local/include/opencv2/core/mat.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/core/opencv2/core/matx.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/core/opencv2/core/types.hpp +opencv2/core/bufferpool.hpp +/usr/local/include/opencv2/core/opencv2/core/bufferpool.hpp +opencv2/core/mat.inl.hpp +/usr/local/include/opencv2/core/opencv2/core/mat.inl.hpp + +/usr/local/include/opencv2/core/mat.inl.hpp + +/usr/local/include/opencv2/core/matx.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/base.hpp +/usr/local/include/opencv2/core/opencv2/core/base.hpp +opencv2/core/traits.hpp +/usr/local/include/opencv2/core/opencv2/core/traits.hpp +opencv2/core/saturate.hpp +/usr/local/include/opencv2/core/opencv2/core/saturate.hpp + +/usr/local/include/opencv2/core/neon_utils.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h + +/usr/local/include/opencv2/core/operations.hpp +cstdio +- + +/usr/local/include/opencv2/core/optim.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/persistence.hpp +opencv2/core/types.hpp +/usr/local/include/opencv2/core/opencv2/core/types.hpp +opencv2/core/mat.hpp +/usr/local/include/opencv2/core/opencv2/core/mat.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/core/opencv2/opencv.hpp +time.h +- + +/usr/local/include/opencv2/core/ptr.inl.hpp +algorithm +- + +/usr/local/include/opencv2/core/saturate.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/fast_math.hpp +/usr/local/include/opencv2/core/opencv2/core/fast_math.hpp + +/usr/local/include/opencv2/core/traits.hpp +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h + +/usr/local/include/opencv2/core/types.hpp +climits +- +cfloat +- +vector +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +opencv2/core/cvstd.hpp +/usr/local/include/opencv2/core/opencv2/core/cvstd.hpp +opencv2/core/matx.hpp +/usr/local/include/opencv2/core/opencv2/core/matx.hpp + +/usr/local/include/opencv2/core/types_c.h +ipl.h +- +ipl/ipl.h +- +opencv2/core/cvdef.h +/usr/local/include/opencv2/core/opencv2/core/cvdef.h +assert.h +- +stdlib.h +- +string.h +- +float.h +- +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp + +/usr/local/include/opencv2/core/utility.hpp +opencv2/core.hpp +/usr/local/include/opencv2/core/opencv2/core.hpp +opencv2/core/core_c.h +/usr/local/include/opencv2/core/opencv2/core/core_c.h + +/usr/local/include/opencv2/core/version.hpp + +/usr/local/include/opencv2/features2d.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/flann/miniflann.hpp +/usr/local/include/opencv2/opencv2/flann/miniflann.hpp + +/usr/local/include/opencv2/features2d/features2d.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/features2d/opencv2/features2d.hpp + +/usr/local/include/opencv2/flann/config.h + +/usr/local/include/opencv2/flann/defines.h +config.h +/usr/local/include/opencv2/flann/config.h + +/usr/local/include/opencv2/flann/miniflann.hpp +opencv2/core.hpp +/usr/local/include/opencv2/flann/opencv2/core.hpp +opencv2/flann/defines.h +/usr/local/include/opencv2/flann/opencv2/flann/defines.h + +/usr/local/include/opencv2/highgui.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgcodecs.hpp +/usr/local/include/opencv2/opencv2/imgcodecs.hpp +opencv2/videoio.hpp +/usr/local/include/opencv2/opencv2/videoio.hpp +opencv2/highgui/highgui_c.h +/usr/local/include/opencv2/opencv2/highgui/highgui_c.h + +/usr/local/include/opencv2/highgui/highgui.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/highgui/opencv2/highgui.hpp + +/usr/local/include/opencv2/highgui/highgui_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/highgui/opencv2/core/core_c.h +opencv2/imgproc/imgproc_c.h +/usr/local/include/opencv2/highgui/opencv2/imgproc/imgproc_c.h +opencv2/imgcodecs/imgcodecs_c.h +/usr/local/include/opencv2/highgui/opencv2/imgcodecs/imgcodecs_c.h +opencv2/videoio/videoio_c.h +/usr/local/include/opencv2/highgui/opencv2/videoio/videoio_c.h + +/usr/local/include/opencv2/imgcodecs.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/opencv.hpp +- + +/usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/imgcodecs/opencv2/core/core_c.h + +/usr/local/include/opencv2/imgproc.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/core.hpp +- +opencv2/imgproc.hpp +- +opencv2/imgcodecs.hpp +- +opencv2/highgui.hpp +- +iostream +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +math.h +- +opencv2/imgproc.hpp +- +opencv2/highgui.hpp +- +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/opencv2/highgui.hpp +opencv2/imgproc/imgproc_c.h +/usr/local/include/opencv2/opencv2/imgproc/imgproc_c.h + +/usr/local/include/opencv2/imgproc/imgproc.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/imgproc/opencv2/imgproc.hpp + +/usr/local/include/opencv2/imgproc/imgproc_c.h +opencv2/imgproc/types_c.h +/usr/local/include/opencv2/imgproc/opencv2/imgproc/types_c.h + +/usr/local/include/opencv2/imgproc/types_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/imgproc/opencv2/core/core_c.h + +/usr/local/include/opencv2/ml.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +float.h +- +map +- +iostream +- + +/usr/local/include/opencv2/objdetect.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/objdetect/detection_based_tracker.hpp +/usr/local/include/opencv2/opencv2/objdetect/detection_based_tracker.hpp +opencv2/objdetect/objdetect_c.h +/usr/local/include/opencv2/opencv2/objdetect/objdetect_c.h + +/usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +vector +- + +/usr/local/include/opencv2/objdetect/objdetect_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/objdetect/opencv2/core/core_c.h +deque +- +vector +- + +/usr/local/include/opencv2/opencv.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/photo.hpp +/usr/local/include/opencv2/opencv2/photo.hpp +opencv2/video.hpp +/usr/local/include/opencv2/opencv2/video.hpp +opencv2/features2d.hpp +/usr/local/include/opencv2/opencv2/features2d.hpp +opencv2/objdetect.hpp +/usr/local/include/opencv2/opencv2/objdetect.hpp +opencv2/calib3d.hpp +/usr/local/include/opencv2/opencv2/calib3d.hpp +opencv2/imgcodecs.hpp +/usr/local/include/opencv2/opencv2/imgcodecs.hpp +opencv2/videoio.hpp +/usr/local/include/opencv2/opencv2/videoio.hpp +opencv2/highgui.hpp +/usr/local/include/opencv2/opencv2/highgui.hpp +opencv2/ml.hpp +/usr/local/include/opencv2/opencv2/ml.hpp + +/usr/local/include/opencv2/photo.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/opencv2/imgproc.hpp +opencv2/photo/photo_c.h +/usr/local/include/opencv2/opencv2/photo/photo_c.h + +/usr/local/include/opencv2/photo/photo_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/photo/opencv2/core/core_c.h + +/usr/local/include/opencv2/video.hpp +opencv2/video/tracking.hpp +/usr/local/include/opencv2/opencv2/video/tracking.hpp +opencv2/video/background_segm.hpp +/usr/local/include/opencv2/opencv2/video/background_segm.hpp +opencv2/video/tracking_c.h +/usr/local/include/opencv2/opencv2/video/tracking_c.h + +/usr/local/include/opencv2/video/background_segm.hpp +opencv2/core.hpp +/usr/local/include/opencv2/video/opencv2/core.hpp + +/usr/local/include/opencv2/video/tracking.hpp +opencv2/core.hpp +/usr/local/include/opencv2/video/opencv2/core.hpp +opencv2/imgproc.hpp +/usr/local/include/opencv2/video/opencv2/imgproc.hpp + +/usr/local/include/opencv2/video/tracking_c.h +opencv2/imgproc/types_c.h +/usr/local/include/opencv2/video/opencv2/imgproc/types_c.h + +/usr/local/include/opencv2/videoio.hpp +opencv2/core.hpp +/usr/local/include/opencv2/opencv2/core.hpp +opencv2/opencv.hpp +/usr/local/include/opencv2/opencv2/opencv.hpp + +/usr/local/include/opencv2/videoio/videoio_c.h +opencv2/core/core_c.h +/usr/local/include/opencv2/videoio/opencv2/core/core_c.h + +/usr/local/include/opencv2/viz.hpp +opencv2/viz/types.hpp +- +opencv2/viz/widgets.hpp +- +opencv2/viz/viz3d.hpp +- +opencv2/viz/vizcore.hpp +- + +/usr/local/include/opencv2/viz/types.hpp +string +- +opencv2/core.hpp +- +opencv2/core/affine.hpp +- + +/usr/local/include/opencv2/viz/viz3d.hpp +opencv2/core.hpp +- +opencv2/viz/types.hpp +- +opencv2/viz/widgets.hpp +- + +/usr/local/include/opencv2/viz/vizcore.hpp +opencv2/viz/types.hpp +- +opencv2/viz/widgets.hpp +- +opencv2/viz/viz3d.hpp +- + +/usr/local/include/opencv2/viz/widgets.hpp +opencv2/viz/types.hpp +- + diff --git a/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/DependInfo.cmake b/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/DependInfo.cmake new file mode 100644 index 00000000..2ba1037b --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/DependInfo.cmake @@ -0,0 +1,26 @@ +# The set of languages for which implicit dependencies are needed: +SET(CMAKE_DEPENDS_LANGUAGES + "CXX" + ) +# The set of files for implicit dependencies of each language: +SET(CMAKE_DEPENDS_CHECK_CXX + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/test/run_vo.cpp" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/run_vo.cpp.o" + ) +SET(CMAKE_CXX_COMPILER_ID "GNU") + +# Targets to which this target links. +SET(CMAKE_TARGET_LINKED_INFO_FILES + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/src/CMakeFiles/myslam.dir/DependInfo.cmake" + ) + +# The include file search paths: +SET(CMAKE_C_TARGET_INCLUDE_PATH + "/usr/include/eigen3" + "/usr/local/include/opencv" + "/usr/local/include" + "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus" + "../include" + ) +SET(CMAKE_CXX_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) +SET(CMAKE_Fortran_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) +SET(CMAKE_ASM_TARGET_INCLUDE_PATH ${CMAKE_C_TARGET_INCLUDE_PATH}) diff --git a/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/build.make b/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/build.make new file mode 100644 index 00000000..de5a20da --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/build.make @@ -0,0 +1,121 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4" + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" + +# Include any dependencies generated for this target. +include test/CMakeFiles/run_vo.dir/depend.make + +# Include the progress variables for this target. +include test/CMakeFiles/run_vo.dir/progress.make + +# Include the compile flags for this target's objects. +include test/CMakeFiles/run_vo.dir/flags.make + +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: test/CMakeFiles/run_vo.dir/flags.make +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: ../test/run_vo.cpp + $(CMAKE_COMMAND) -E cmake_progress_report "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles" $(CMAKE_PROGRESS_1) + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Building CXX object test/CMakeFiles/run_vo.dir/run_vo.cpp.o" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/test" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -o CMakeFiles/run_vo.dir/run_vo.cpp.o -c "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/test/run_vo.cpp" + +test/CMakeFiles/run_vo.dir/run_vo.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/run_vo.dir/run_vo.cpp.i" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/test" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -E "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/test/run_vo.cpp" > CMakeFiles/run_vo.dir/run_vo.cpp.i + +test/CMakeFiles/run_vo.dir/run_vo.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/run_vo.dir/run_vo.cpp.s" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/test" && g++ $(CXX_DEFINES) $(CXX_FLAGS) -S "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/test/run_vo.cpp" -o CMakeFiles/run_vo.dir/run_vo.cpp.s + +test/CMakeFiles/run_vo.dir/run_vo.cpp.o.requires: +.PHONY : test/CMakeFiles/run_vo.dir/run_vo.cpp.o.requires + +test/CMakeFiles/run_vo.dir/run_vo.cpp.o.provides: test/CMakeFiles/run_vo.dir/run_vo.cpp.o.requires + $(MAKE) -f test/CMakeFiles/run_vo.dir/build.make test/CMakeFiles/run_vo.dir/run_vo.cpp.o.provides.build +.PHONY : test/CMakeFiles/run_vo.dir/run_vo.cpp.o.provides + +test/CMakeFiles/run_vo.dir/run_vo.cpp.o.provides.build: test/CMakeFiles/run_vo.dir/run_vo.cpp.o + +# Object files for target run_vo +run_vo_OBJECTS = \ +"CMakeFiles/run_vo.dir/run_vo.cpp.o" + +# External object files for target run_vo +run_vo_EXTERNAL_OBJECTS = + +../bin/run_vo: test/CMakeFiles/run_vo.dir/run_vo.cpp.o +../bin/run_vo: test/CMakeFiles/run_vo.dir/build.make +../bin/run_vo: ../lib/libmyslam.so +../bin/run_vo: /usr/local/lib/libopencv_viz.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_videostab.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_superres.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_stitching.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_shape.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_video.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_photo.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_objdetect.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_calib3d.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_features2d.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_ml.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_highgui.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_videoio.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_imgcodecs.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_imgproc.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_flann.so.3.1.0 +../bin/run_vo: /usr/local/lib/libopencv_core.so.3.1.0 +../bin/run_vo: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build/libSophus.so +../bin/run_vo: test/CMakeFiles/run_vo.dir/link.txt + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --red --bold "Linking CXX executable ../../bin/run_vo" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/test" && $(CMAKE_COMMAND) -E cmake_link_script CMakeFiles/run_vo.dir/link.txt --verbose=$(VERBOSE) + +# Rule to build all files generated by this target. +test/CMakeFiles/run_vo.dir/build: ../bin/run_vo +.PHONY : test/CMakeFiles/run_vo.dir/build + +test/CMakeFiles/run_vo.dir/requires: test/CMakeFiles/run_vo.dir/run_vo.cpp.o.requires +.PHONY : test/CMakeFiles/run_vo.dir/requires + +test/CMakeFiles/run_vo.dir/clean: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/test" && $(CMAKE_COMMAND) -P CMakeFiles/run_vo.dir/cmake_clean.cmake +.PHONY : test/CMakeFiles/run_vo.dir/clean + +test/CMakeFiles/run_vo.dir/depend: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/test" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/test" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/DependInfo.cmake" --color=$(COLOR) +.PHONY : test/CMakeFiles/run_vo.dir/depend + diff --git a/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/cmake_clean.cmake b/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/cmake_clean.cmake new file mode 100644 index 00000000..6f7a8a1e --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/cmake_clean.cmake @@ -0,0 +1,10 @@ +FILE(REMOVE_RECURSE + "CMakeFiles/run_vo.dir/run_vo.cpp.o" + "../../bin/run_vo.pdb" + "../../bin/run_vo" +) + +# Per-language clean rules from dependency scanning. +FOREACH(lang CXX) + INCLUDE(CMakeFiles/run_vo.dir/cmake_clean_${lang}.cmake OPTIONAL) +ENDFOREACH(lang) diff --git a/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/depend.internal b/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/depend.internal new file mode 100644 index 00000000..980cdc53 --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/depend.internal @@ -0,0 +1,278 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +test/CMakeFiles/run_vo.dir/run_vo.cpp.o + ../include/myslam/camera.h + ../include/myslam/common_include.h + ../include/myslam/config.h + ../include/myslam/frame.h + ../include/myslam/map.h + ../include/myslam/mappoint.h + ../include/myslam/visual_odometry.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h + /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/test/run_vo.cpp + /usr/include/eigen3/Eigen/Cholesky + /usr/include/eigen3/Eigen/Core + /usr/include/eigen3/Eigen/Eigen2Support + /usr/include/eigen3/Eigen/Eigenvalues + /usr/include/eigen3/Eigen/Geometry + /usr/include/eigen3/Eigen/Householder + /usr/include/eigen3/Eigen/Jacobi + /usr/include/eigen3/Eigen/LU + /usr/include/eigen3/Eigen/QR + /usr/include/eigen3/Eigen/SVD + /usr/include/eigen3/Eigen/StdVector + /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT.h + /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h + /usr/include/eigen3/Eigen/src/Core/Array.h + /usr/include/eigen3/Eigen/src/Core/ArrayBase.h + /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h + /usr/include/eigen3/Eigen/src/Core/Assign.h + /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h + /usr/include/eigen3/Eigen/src/Core/BandMatrix.h + /usr/include/eigen3/Eigen/src/Core/Block.h + /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h + /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h + /usr/include/eigen3/Eigen/src/Core/CoreIterators.h + /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h + /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h + /usr/include/eigen3/Eigen/src/Core/DenseBase.h + /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h + /usr/include/eigen3/Eigen/src/Core/DenseStorage.h + /usr/include/eigen3/Eigen/src/Core/Diagonal.h + /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h + /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h + /usr/include/eigen3/Eigen/src/Core/Dot.h + /usr/include/eigen3/Eigen/src/Core/EigenBase.h + /usr/include/eigen3/Eigen/src/Core/Flagged.h + /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h + /usr/include/eigen3/Eigen/src/Core/Functors.h + /usr/include/eigen3/Eigen/src/Core/Fuzzy.h + /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h + /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h + /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h + /usr/include/eigen3/Eigen/src/Core/IO.h + /usr/include/eigen3/Eigen/src/Core/Map.h + /usr/include/eigen3/Eigen/src/Core/MapBase.h + /usr/include/eigen3/Eigen/src/Core/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/Matrix.h + /usr/include/eigen3/Eigen/src/Core/MatrixBase.h + /usr/include/eigen3/Eigen/src/Core/NestByValue.h + /usr/include/eigen3/Eigen/src/Core/NoAlias.h + /usr/include/eigen3/Eigen/src/Core/NumTraits.h + /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h + /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h + /usr/include/eigen3/Eigen/src/Core/ProductBase.h + /usr/include/eigen3/Eigen/src/Core/Random.h + /usr/include/eigen3/Eigen/src/Core/Redux.h + /usr/include/eigen3/Eigen/src/Core/Ref.h + /usr/include/eigen3/Eigen/src/Core/Replicate.h + /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h + /usr/include/eigen3/Eigen/src/Core/Reverse.h + /usr/include/eigen3/Eigen/src/Core/Select.h + /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h + /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h + /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h + /usr/include/eigen3/Eigen/src/Core/StableNorm.h + /usr/include/eigen3/Eigen/src/Core/Stride.h + /usr/include/eigen3/Eigen/src/Core/Swap.h + /usr/include/eigen3/Eigen/src/Core/Transpose.h + /usr/include/eigen3/Eigen/src/Core/Transpositions.h + /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h + /usr/include/eigen3/Eigen/src/Core/VectorBlock.h + /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h + /usr/include/eigen3/Eigen/src/Core/Visitor.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h + /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h + /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h + /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h + /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h + /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h + /usr/include/eigen3/Eigen/src/Core/util/Constants.h + /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h + /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h + /usr/include/eigen3/Eigen/src/Core/util/Macros.h + /usr/include/eigen3/Eigen/src/Core/util/Memory.h + /usr/include/eigen3/Eigen/src/Core/util/Meta.h + /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h + /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h + /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h + /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h + /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h + /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h + /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h + /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h + /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h + /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h + /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h + /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h + /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h + /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h + /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h + /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h + /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h + /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h + /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h + /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h + /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h + /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h + /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h + /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h + /usr/include/eigen3/Eigen/src/Geometry/Scaling.h + /usr/include/eigen3/Eigen/src/Geometry/Transform.h + /usr/include/eigen3/Eigen/src/Geometry/Translation.h + /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h + /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h + /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h + /usr/include/eigen3/Eigen/src/Householder/Householder.h + /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h + /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h + /usr/include/eigen3/Eigen/src/LU/Determinant.h + /usr/include/eigen3/Eigen/src/LU/FullPivLU.h + /usr/include/eigen3/Eigen/src/LU/Inverse.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h + /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h + /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h + /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h + /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h + /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h + /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h + /usr/include/eigen3/Eigen/src/StlSupport/details.h + /usr/include/eigen3/Eigen/src/misc/Image.h + /usr/include/eigen3/Eigen/src/misc/Kernel.h + /usr/include/eigen3/Eigen/src/misc/Solve.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h + /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h + /usr/local/include/opencv/cxcore.h + /usr/local/include/opencv2/calib3d.hpp + /usr/local/include/opencv2/calib3d/calib3d_c.h + /usr/local/include/opencv2/core.hpp + /usr/local/include/opencv2/core/affine.hpp + /usr/local/include/opencv2/core/base.hpp + /usr/local/include/opencv2/core/bufferpool.hpp + /usr/local/include/opencv2/core/core.hpp + /usr/local/include/opencv2/core/core_c.h + /usr/local/include/opencv2/core/cvdef.h + /usr/local/include/opencv2/core/cvstd.hpp + /usr/local/include/opencv2/core/cvstd.inl.hpp + /usr/local/include/opencv2/core/fast_math.hpp + /usr/local/include/opencv2/core/hal/interface.h + /usr/local/include/opencv2/core/mat.hpp + /usr/local/include/opencv2/core/mat.inl.hpp + /usr/local/include/opencv2/core/matx.hpp + /usr/local/include/opencv2/core/neon_utils.hpp + /usr/local/include/opencv2/core/operations.hpp + /usr/local/include/opencv2/core/optim.hpp + /usr/local/include/opencv2/core/persistence.hpp + /usr/local/include/opencv2/core/ptr.inl.hpp + /usr/local/include/opencv2/core/saturate.hpp + /usr/local/include/opencv2/core/traits.hpp + /usr/local/include/opencv2/core/types.hpp + /usr/local/include/opencv2/core/types_c.h + /usr/local/include/opencv2/core/utility.hpp + /usr/local/include/opencv2/core/version.hpp + /usr/local/include/opencv2/features2d.hpp + /usr/local/include/opencv2/features2d/features2d.hpp + /usr/local/include/opencv2/flann/config.h + /usr/local/include/opencv2/flann/defines.h + /usr/local/include/opencv2/flann/miniflann.hpp + /usr/local/include/opencv2/highgui.hpp + /usr/local/include/opencv2/highgui/highgui.hpp + /usr/local/include/opencv2/highgui/highgui_c.h + /usr/local/include/opencv2/imgcodecs.hpp + /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h + /usr/local/include/opencv2/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc.hpp + /usr/local/include/opencv2/imgproc/imgproc_c.h + /usr/local/include/opencv2/imgproc/types_c.h + /usr/local/include/opencv2/ml.hpp + /usr/local/include/opencv2/objdetect.hpp + /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp + /usr/local/include/opencv2/objdetect/objdetect_c.h + /usr/local/include/opencv2/opencv.hpp + /usr/local/include/opencv2/photo.hpp + /usr/local/include/opencv2/photo/photo_c.h + /usr/local/include/opencv2/video.hpp + /usr/local/include/opencv2/video/background_segm.hpp + /usr/local/include/opencv2/video/tracking.hpp + /usr/local/include/opencv2/video/tracking_c.h + /usr/local/include/opencv2/videoio.hpp + /usr/local/include/opencv2/videoio/videoio_c.h + /usr/local/include/opencv2/viz.hpp + /usr/local/include/opencv2/viz/types.hpp + /usr/local/include/opencv2/viz/viz3d.hpp + /usr/local/include/opencv2/viz/vizcore.hpp + /usr/local/include/opencv2/viz/widgets.hpp diff --git a/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/depend.make b/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/depend.make new file mode 100644 index 00000000..6df28710 --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/depend.make @@ -0,0 +1,278 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: ../include/myslam/camera.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: ../include/myslam/common_include.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: ../include/myslam/config.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: ../include/myslam/frame.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: ../include/myslam/map.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: ../include/myslam/mappoint.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: ../include/myslam/visual_odometry.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/se3.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/sophus/so3.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: ../test/run_vo.cpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/Cholesky +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/Core +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/Eigen2Support +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/Geometry +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/Householder +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/Jacobi +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/LU +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/QR +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/SVD +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/StdVector +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Flagged.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/ForceAlignedAccess.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Functors.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/CoeffBasedProduct.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Block.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Cwise.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/CwiseOperators.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AlignedBox.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/All.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/AngleAxis.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Hyperplane.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Quaternion.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Rotation2D.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/RotationBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Scaling.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Transform.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Geometry/Translation.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/LU.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Lazy.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Macros.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/MathFunctions.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Memory.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Meta.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/Minor.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/QR.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/SVD.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/TriangularSolver.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigen2Support/VectorBlock.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/LU/Inverse.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/misc/Solve.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv/cxcore.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/calib3d.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/calib3d/calib3d_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/affine.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/base.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/bufferpool.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/core.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/core_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/cvdef.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/cvstd.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/cvstd.inl.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/fast_math.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/hal/interface.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/mat.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/mat.inl.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/matx.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/neon_utils.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/operations.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/optim.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/persistence.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/ptr.inl.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/saturate.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/traits.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/types.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/types_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/utility.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/core/version.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/features2d.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/features2d/features2d.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/flann/config.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/flann/defines.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/flann/miniflann.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/highgui.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/highgui/highgui.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/highgui/highgui_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/imgcodecs.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/imgcodecs/imgcodecs_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/imgproc.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/imgproc/imgproc.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/imgproc/imgproc_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/imgproc/types_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/ml.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/objdetect.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/objdetect/detection_based_tracker.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/objdetect/objdetect_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/opencv.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/photo.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/photo/photo_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/video.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/video/background_segm.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/video/tracking.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/video/tracking_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/videoio.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/videoio/videoio_c.h +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/viz.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/viz/types.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/viz/viz3d.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/viz/vizcore.hpp +test/CMakeFiles/run_vo.dir/run_vo.cpp.o: /usr/local/include/opencv2/viz/widgets.hpp + diff --git a/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/flags.make b/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/flags.make new file mode 100644 index 00000000..fa65eaca --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/flags.make @@ -0,0 +1,8 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# compile CXX with g++ +CXX_FLAGS = -std=c++11 -march=native -O3 -O3 -DNDEBUG -I/usr/include/eigen3 -I/usr/local/include/opencv -I/usr/local/include -I/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus -I"/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/include" + +CXX_DEFINES = + diff --git a/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/link.txt b/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/link.txt new file mode 100644 index 00000000..4c6088a0 --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/link.txt @@ -0,0 +1 @@ +g++ -std=c++11 -march=native -O3 -O3 -DNDEBUG CMakeFiles/run_vo.dir/run_vo.cpp.o -o ../../bin/run_vo -rdynamic ../../lib/libmyslam.so /usr/local/lib/libopencv_viz.so.3.1.0 /usr/local/lib/libopencv_videostab.so.3.1.0 /usr/local/lib/libopencv_superres.so.3.1.0 /usr/local/lib/libopencv_stitching.so.3.1.0 /usr/local/lib/libopencv_shape.so.3.1.0 /usr/local/lib/libopencv_video.so.3.1.0 /usr/local/lib/libopencv_photo.so.3.1.0 /usr/local/lib/libopencv_objdetect.so.3.1.0 /usr/local/lib/libopencv_calib3d.so.3.1.0 /usr/local/lib/libopencv_features2d.so.3.1.0 /usr/local/lib/libopencv_ml.so.3.1.0 /usr/local/lib/libopencv_highgui.so.3.1.0 /usr/local/lib/libopencv_videoio.so.3.1.0 /usr/local/lib/libopencv_imgcodecs.so.3.1.0 /usr/local/lib/libopencv_imgproc.so.3.1.0 /usr/local/lib/libopencv_flann.so.3.1.0 /usr/local/lib/libopencv_core.so.3.1.0 /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build/libSophus.so -lg2o_core -lg2o_stuff -lg2o_types_sba -Wl,-rpath,"/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/lib:/usr/local/lib:/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch4/Sophus/build" diff --git a/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/progress.make b/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/progress.make new file mode 100644 index 00000000..c561fcae --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/progress.make @@ -0,0 +1,2 @@ +CMAKE_PROGRESS_1 = 8 + diff --git a/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/run_vo.cpp.o b/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/run_vo.cpp.o new file mode 100644 index 00000000..89c076f6 Binary files /dev/null and b/vSLAM/ch9 project/0.4/build/test/CMakeFiles/run_vo.dir/run_vo.cpp.o differ diff --git a/vSLAM/ch9 project/0.4/build/test/Makefile b/vSLAM/ch9 project/0.4/build/test/Makefile new file mode 100644 index 00000000..b89eebaa --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/test/Makefile @@ -0,0 +1,164 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 2.8 + +# Default target executed when no arguments are given to make. +default_target: all +.PHONY : default_target + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Remove some rules from gmake that .SUFFIXES does not remove. +SUFFIXES = + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E remove -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4" + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" + +#============================================================================= +# Targets provided globally by CMake. + +# Special rule for the target edit_cache +edit_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running interactive CMake command-line interface..." + /usr/bin/cmake -i . +.PHONY : edit_cache + +# Special rule for the target edit_cache +edit_cache/fast: edit_cache +.PHONY : edit_cache/fast + +# Special rule for the target rebuild_cache +rebuild_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake to regenerate build system..." + /usr/bin/cmake -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) +.PHONY : rebuild_cache + +# Special rule for the target rebuild_cache +rebuild_cache/fast: rebuild_cache +.PHONY : rebuild_cache/fast + +# The main all target +all: cmake_check_build_system + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles" "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/test/CMakeFiles/progress.marks" + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f CMakeFiles/Makefile2 test/all + $(CMAKE_COMMAND) -E cmake_progress_start "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build/CMakeFiles" 0 +.PHONY : all + +# The main clean target +clean: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f CMakeFiles/Makefile2 test/clean +.PHONY : clean + +# The main clean target +clean/fast: clean +.PHONY : clean/fast + +# Prepare targets for installation. +preinstall: all + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f CMakeFiles/Makefile2 test/preinstall +.PHONY : preinstall + +# Prepare targets for installation. +preinstall/fast: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f CMakeFiles/Makefile2 test/preinstall +.PHONY : preinstall/fast + +# clear depends +depend: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 1 +.PHONY : depend + +# Convenience name for target. +test/CMakeFiles/run_vo.dir/rule: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f CMakeFiles/Makefile2 test/CMakeFiles/run_vo.dir/rule +.PHONY : test/CMakeFiles/run_vo.dir/rule + +# Convenience name for target. +run_vo: test/CMakeFiles/run_vo.dir/rule +.PHONY : run_vo + +# fast build rule for target. +run_vo/fast: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f test/CMakeFiles/run_vo.dir/build.make test/CMakeFiles/run_vo.dir/build +.PHONY : run_vo/fast + +run_vo.o: run_vo.cpp.o +.PHONY : run_vo.o + +# target to build an object file +run_vo.cpp.o: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f test/CMakeFiles/run_vo.dir/build.make test/CMakeFiles/run_vo.dir/run_vo.cpp.o +.PHONY : run_vo.cpp.o + +run_vo.i: run_vo.cpp.i +.PHONY : run_vo.i + +# target to preprocess a source file +run_vo.cpp.i: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f test/CMakeFiles/run_vo.dir/build.make test/CMakeFiles/run_vo.dir/run_vo.cpp.i +.PHONY : run_vo.cpp.i + +run_vo.s: run_vo.cpp.s +.PHONY : run_vo.s + +# target to generate assembly for a file +run_vo.cpp.s: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(MAKE) -f test/CMakeFiles/run_vo.dir/build.make test/CMakeFiles/run_vo.dir/run_vo.cpp.s +.PHONY : run_vo.cpp.s + +# Help Target +help: + @echo "The following are some of the valid targets for this Makefile:" + @echo "... all (the default if no target is provided)" + @echo "... clean" + @echo "... depend" + @echo "... edit_cache" + @echo "... rebuild_cache" + @echo "... run_vo" + @echo "... run_vo.o" + @echo "... run_vo.i" + @echo "... run_vo.s" +.PHONY : help + + + +#============================================================================= +# Special targets to cleanup operation of make. + +# Special rule to run CMake to check the build system integrity. +# No rule that depends on this can have commands that come from listfiles +# because they might be regenerated. +cmake_check_build_system: + cd "/home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/build" && $(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0 +.PHONY : cmake_check_build_system + diff --git a/vSLAM/ch9 project/0.4/build/test/cmake_install.cmake b/vSLAM/ch9 project/0.4/build/test/cmake_install.cmake new file mode 100644 index 00000000..ccf6b68f --- /dev/null +++ b/vSLAM/ch9 project/0.4/build/test/cmake_install.cmake @@ -0,0 +1,34 @@ +# Install script for directory: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch9 project/0.4/test + +# Set the install prefix +IF(NOT DEFINED CMAKE_INSTALL_PREFIX) + SET(CMAKE_INSTALL_PREFIX "/usr/local") +ENDIF(NOT DEFINED CMAKE_INSTALL_PREFIX) +STRING(REGEX REPLACE "/$" "" CMAKE_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}") + +# Set the install configuration name. +IF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + IF(BUILD_TYPE) + STRING(REGEX REPLACE "^[^A-Za-z0-9_]+" "" + CMAKE_INSTALL_CONFIG_NAME "${BUILD_TYPE}") + ELSE(BUILD_TYPE) + SET(CMAKE_INSTALL_CONFIG_NAME "Release") + ENDIF(BUILD_TYPE) + MESSAGE(STATUS "Install configuration: \"${CMAKE_INSTALL_CONFIG_NAME}\"") +ENDIF(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + +# Set the component getting installed. +IF(NOT CMAKE_INSTALL_COMPONENT) + IF(COMPONENT) + MESSAGE(STATUS "Install component: \"${COMPONENT}\"") + SET(CMAKE_INSTALL_COMPONENT "${COMPONENT}") + ELSE(COMPONENT) + SET(CMAKE_INSTALL_COMPONENT) + ENDIF(COMPONENT) +ENDIF(NOT CMAKE_INSTALL_COMPONENT) + +# Install shared libraries without execute permission? +IF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + SET(CMAKE_INSTALL_SO_NO_EXE "1") +ENDIF(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + diff --git a/vSLAM/ch9 project/0.4/cmake_modules/FindCSparse.cmake b/vSLAM/ch9 project/0.4/cmake_modules/FindCSparse.cmake new file mode 100644 index 00000000..f31df8de --- /dev/null +++ b/vSLAM/ch9 project/0.4/cmake_modules/FindCSparse.cmake @@ -0,0 +1,25 @@ +# Look for csparse; note the difference in the directory specifications! +FIND_PATH(CSPARSE_INCLUDE_DIR NAMES cs.h + PATHS + /usr/include/suitesparse + /usr/include + /opt/local/include + /usr/local/include + /sw/include + /usr/include/ufsparse + /opt/local/include/ufsparse + /usr/local/include/ufsparse + /sw/include/ufsparse + ) + +FIND_LIBRARY(CSPARSE_LIBRARY NAMES cxsparse + PATHS + /usr/lib + /usr/local/lib + /opt/local/lib + /sw/lib + ) + +include(FindPackageHandleStandardArgs) +find_package_handle_standard_args(CSPARSE DEFAULT_MSG + CSPARSE_INCLUDE_DIR CSPARSE_LIBRARY) diff --git a/vSLAM/ch9 project/0.4/cmake_modules/FindG2O.cmake b/vSLAM/ch9 project/0.4/cmake_modules/FindG2O.cmake new file mode 100644 index 00000000..655600fb --- /dev/null +++ b/vSLAM/ch9 project/0.4/cmake_modules/FindG2O.cmake @@ -0,0 +1,113 @@ +# Find the header files + +FIND_PATH(G2O_INCLUDE_DIR g2o/core/base_vertex.h + ${G2O_ROOT}/include + $ENV{G2O_ROOT}/include + $ENV{G2O_ROOT} + /usr/local/include + /usr/include + /opt/local/include + /sw/local/include + /sw/include + NO_DEFAULT_PATH + ) + +# Macro to unify finding both the debug and release versions of the +# libraries; this is adapted from the OpenSceneGraph FIND_LIBRARY +# macro. + +MACRO(FIND_G2O_LIBRARY MYLIBRARY MYLIBRARYNAME) + + FIND_LIBRARY("${MYLIBRARY}_DEBUG" + NAMES "g2o_${MYLIBRARYNAME}_d" + PATHS + ${G2O_ROOT}/lib/Debug + ${G2O_ROOT}/lib + $ENV{G2O_ROOT}/lib/Debug + $ENV{G2O_ROOT}/lib + NO_DEFAULT_PATH + ) + + FIND_LIBRARY("${MYLIBRARY}_DEBUG" + NAMES "g2o_${MYLIBRARYNAME}_d" + PATHS + ~/Library/Frameworks + /Library/Frameworks + /usr/local/lib + /usr/local/lib64 + /usr/lib + /usr/lib64 + /opt/local/lib + /sw/local/lib + /sw/lib + ) + + FIND_LIBRARY(${MYLIBRARY} + NAMES "g2o_${MYLIBRARYNAME}" + PATHS + ${G2O_ROOT}/lib/Release + ${G2O_ROOT}/lib + $ENV{G2O_ROOT}/lib/Release + $ENV{G2O_ROOT}/lib + NO_DEFAULT_PATH + ) + + FIND_LIBRARY(${MYLIBRARY} + NAMES "g2o_${MYLIBRARYNAME}" + PATHS + ~/Library/Frameworks + /Library/Frameworks + /usr/local/lib + /usr/local/lib64 + /usr/lib + /usr/lib64 + /opt/local/lib + /sw/local/lib + /sw/lib + ) + + IF(NOT ${MYLIBRARY}_DEBUG) + IF(MYLIBRARY) + SET(${MYLIBRARY}_DEBUG ${MYLIBRARY}) + ENDIF(MYLIBRARY) + ENDIF( NOT ${MYLIBRARY}_DEBUG) + +ENDMACRO(FIND_G2O_LIBRARY LIBRARY LIBRARYNAME) + +# Find the core elements +FIND_G2O_LIBRARY(G2O_STUFF_LIBRARY stuff) +FIND_G2O_LIBRARY(G2O_CORE_LIBRARY core) + +# Find the CLI library +FIND_G2O_LIBRARY(G2O_CLI_LIBRARY cli) + +# Find the pluggable solvers +FIND_G2O_LIBRARY(G2O_SOLVER_CHOLMOD solver_cholmod) +FIND_G2O_LIBRARY(G2O_SOLVER_CSPARSE solver_csparse) +FIND_G2O_LIBRARY(G2O_SOLVER_CSPARSE_EXTENSION csparse_extension) +FIND_G2O_LIBRARY(G2O_SOLVER_DENSE solver_dense) +FIND_G2O_LIBRARY(G2O_SOLVER_PCG solver_pcg) +FIND_G2O_LIBRARY(G2O_SOLVER_SLAM2D_LINEAR solver_slam2d_linear) +FIND_G2O_LIBRARY(G2O_SOLVER_STRUCTURE_ONLY solver_structure_only) +FIND_G2O_LIBRARY(G2O_SOLVER_EIGEN solver_eigen) + +# Find the predefined types +FIND_G2O_LIBRARY(G2O_TYPES_DATA types_data) +FIND_G2O_LIBRARY(G2O_TYPES_ICP types_icp) +FIND_G2O_LIBRARY(G2O_TYPES_SBA types_sba) +FIND_G2O_LIBRARY(G2O_TYPES_SCLAM2D types_sclam2d) +FIND_G2O_LIBRARY(G2O_TYPES_SIM3 types_sim3) +FIND_G2O_LIBRARY(G2O_TYPES_SLAM2D types_slam2d) +FIND_G2O_LIBRARY(G2O_TYPES_SLAM3D types_slam3d) + +# G2O solvers declared found if we found at least one solver +SET(G2O_SOLVERS_FOUND "NO") +IF(G2O_SOLVER_CHOLMOD OR G2O_SOLVER_CSPARSE OR G2O_SOLVER_DENSE OR G2O_SOLVER_PCG OR G2O_SOLVER_SLAM2D_LINEAR OR G2O_SOLVER_STRUCTURE_ONLY OR G2O_SOLVER_EIGEN) + SET(G2O_SOLVERS_FOUND "YES") +ENDIF(G2O_SOLVER_CHOLMOD OR G2O_SOLVER_CSPARSE OR G2O_SOLVER_DENSE OR G2O_SOLVER_PCG OR G2O_SOLVER_SLAM2D_LINEAR OR G2O_SOLVER_STRUCTURE_ONLY OR G2O_SOLVER_EIGEN) + +# G2O itself declared found if we found the core libraries and at least one solver +SET(G2O_FOUND "NO") +IF(G2O_STUFF_LIBRARY AND G2O_CORE_LIBRARY AND G2O_INCLUDE_DIR AND G2O_SOLVERS_FOUND) + SET(G2O_FOUND "YES") +ENDIF(G2O_STUFF_LIBRARY AND G2O_CORE_LIBRARY AND G2O_INCLUDE_DIR AND G2O_SOLVERS_FOUND) diff --git a/vSLAM/ch9 project/0.4/config/default.yaml b/vSLAM/ch9 project/0.4/config/default.yaml new file mode 100644 index 00000000..7b75244a --- /dev/null +++ b/vSLAM/ch9 project/0.4/config/default.yaml @@ -0,0 +1,30 @@ +%YAML:1.0 +# data +# the tum dataset directory, change it to yours! +dataset_dir: /home/ewenwan/ewenwan/learn/vSLAM/test/vSLAM/ch8/data + +# camera intrinsics +# fr1 +camera.fx: 517.3 +camera.fy: 516.5 +camera.cx: 325.1 +camera.cy: 249.7 + +# fr2 +#camera.fx: 520.9 +#camera.fy: 521.0 +#camera.cx: 325.1 +#camera.cy: 249.7 + +camera.depth_scale: 5000 + +# VO Parameters +number_of_features: 500 +scale_factor: 1.2 +level_pyramid: 4 +match_ratio: 2.0 +max_num_lost: 10 +min_inliers: 30 +keyframe_rotation: 0.1 +keyframe_translation: 0.1 +map_point_erase_ratio: 0.1 diff --git a/vSLAM/ch9 project/0.4/include/myslam/camera.h b/vSLAM/ch9 project/0.4/include/myslam/camera.h new file mode 100644 index 00000000..bace0652 --- /dev/null +++ b/vSLAM/ch9 project/0.4/include/myslam/camera.h @@ -0,0 +1,51 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifndef CAMERA_H +#define CAMERA_H + +#include "myslam/common_include.h" + +namespace myslam +{ + +// Pinhole RGBD camera model +class Camera +{ +public: + typedef std::shared_ptr Ptr; + float fx_, fy_, cx_, cy_, depth_scale_; + + Camera(); + Camera ( float fx, float fy, float cx, float cy, float depth_scale=0 ) : + fx_ ( fx ), fy_ ( fy ), cx_ ( cx ), cy_ ( cy ), depth_scale_ ( depth_scale ) + {} + + // coordinate transform: world, camera, pixel + Vector3d world2camera( const Vector3d& p_w, const SE3& T_c_w ); + Vector3d camera2world( const Vector3d& p_c, const SE3& T_c_w ); + Vector2d camera2pixel( const Vector3d& p_c ); + Vector3d pixel2camera( const Vector2d& p_p, double depth=1 ); + Vector3d pixel2world ( const Vector2d& p_p, const SE3& T_c_w, double depth=1 ); + Vector2d world2pixel ( const Vector3d& p_w, const SE3& T_c_w ); + +}; + +} +#endif // CAMERA_H diff --git a/vSLAM/ch9 project/0.4/include/myslam/common_include.h b/vSLAM/ch9 project/0.4/include/myslam/common_include.h new file mode 100644 index 00000000..a8f7e4cd --- /dev/null +++ b/vSLAM/ch9 project/0.4/include/myslam/common_include.h @@ -0,0 +1,52 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + + +#ifndef COMMON_INCLUDE_H +#define COMMON_INCLUDE_H + +// define the commonly included file to avoid a long include list +// for Eigen +#include +#include +using Eigen::Vector2d; +using Eigen::Vector3d; + +// for Sophus +#include +#include +using Sophus::SO3; +using Sophus::SE3; + +// for cv +#include +using cv::Mat; + +// std +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace std; +#endif \ No newline at end of file diff --git a/vSLAM/ch9 project/0.4/include/myslam/config.h b/vSLAM/ch9 project/0.4/include/myslam/config.h new file mode 100644 index 00000000..f5c7b452 --- /dev/null +++ b/vSLAM/ch9 project/0.4/include/myslam/config.h @@ -0,0 +1,49 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifndef CONFIG_H +#define CONFIG_H + +#include "myslam/common_include.h" + +namespace myslam +{ +class Config +{ +private: + static std::shared_ptr config_; + cv::FileStorage file_; + + Config () {} // private constructor makes a singleton +public: + ~Config(); // close the file when deconstructing + + // set a new config file + static void setParameterFile( const std::string& filename ); + + // access the parameter values + template< typename T > + static T get( const std::string& key ) + { + return T( Config::config_->file_[key] ); + } +}; +} + +#endif // CONFIG_H diff --git a/vSLAM/ch9 project/0.4/include/myslam/frame.h b/vSLAM/ch9 project/0.4/include/myslam/frame.h new file mode 100644 index 00000000..e0d4ce48 --- /dev/null +++ b/vSLAM/ch9 project/0.4/include/myslam/frame.h @@ -0,0 +1,65 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifndef FRAME_H +#define FRAME_H + +#include "myslam/common_include.h" +#include "myslam/camera.h" + +namespace myslam +{ + +// forward declare +class MapPoint; +class Frame +{ +public: + typedef std::shared_ptr Ptr; + unsigned long id_; // id of this frame + double time_stamp_; // when it is recorded + SE3 T_c_w_; // transform from world to camera + Camera::Ptr camera_; // Pinhole RGBD Camera model + Mat color_, depth_; // color and depth image + // std::vector keypoints_; // key points in image + // std::vector map_points_; // associated map points + bool is_key_frame_; // whether a key-frame + +public: // data members + Frame(); + Frame( long id, double time_stamp=0, SE3 T_c_w=SE3(), Camera::Ptr camera=nullptr, Mat color=Mat(), Mat depth=Mat() ); + ~Frame(); + + static Frame::Ptr createFrame(); + + // find the depth in depth map + double findDepth( const cv::KeyPoint& kp ); + + // Get Camera Center + Vector3d getCamCenter() const; + + void setPose( const SE3& T_c_w ); + + // check if a point is in this frame + bool isInFrame( const Vector3d& pt_world ); +}; + +} + +#endif // FRAME_H diff --git a/vSLAM/ch9 project/0.4/include/myslam/g2o_types.h b/vSLAM/ch9 project/0.4/include/myslam/g2o_types.h new file mode 100644 index 00000000..aacbcf64 --- /dev/null +++ b/vSLAM/ch9 project/0.4/include/myslam/g2o_types.h @@ -0,0 +1,81 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifndef MYSLAM_G2O_TYPES_H +#define MYSLAM_G2O_TYPES_H + +#include "myslam/common_include.h" +#include "camera.h" + +#include +#include +#include +#include +#include +#include +#include +#include + +namespace myslam +{ +class EdgeProjectXYZRGBD : public g2o::BaseBinaryEdge<3, Eigen::Vector3d, g2o::VertexSBAPointXYZ, g2o::VertexSE3Expmap> +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW; + virtual void computeError(); + virtual void linearizeOplus(); + virtual bool read( std::istream& in ){} + virtual bool write( std::ostream& out) const {} + +}; + +// only to optimize the pose, no point +class EdgeProjectXYZRGBDPoseOnly: public g2o::BaseUnaryEdge<3, Eigen::Vector3d, g2o::VertexSE3Expmap > +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + // Error: measure = R*point+t + virtual void computeError(); + virtual void linearizeOplus(); + + virtual bool read( std::istream& in ){} + virtual bool write( std::ostream& out) const {} + + Vector3d point_; +}; + +class EdgeProjectXYZ2UVPoseOnly: public g2o::BaseUnaryEdge<2, Eigen::Vector2d, g2o::VertexSE3Expmap > +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + virtual void computeError(); + virtual void linearizeOplus(); + + virtual bool read( std::istream& in ){} + virtual bool write(std::ostream& os) const {}; + + Vector3d point_; + Camera* camera_; +}; + +} + + +#endif // MYSLAM_G2O_TYPES_H diff --git a/vSLAM/ch9 project/0.4/include/myslam/map.h b/vSLAM/ch9 project/0.4/include/myslam/map.h new file mode 100644 index 00000000..f37547ca --- /dev/null +++ b/vSLAM/ch9 project/0.4/include/myslam/map.h @@ -0,0 +1,43 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifndef MAP_H +#define MAP_H + +#include "myslam/common_include.h" +#include "myslam/frame.h" +#include "myslam/mappoint.h" + +namespace myslam +{ +class Map +{ +public: + typedef shared_ptr Ptr; + unordered_map map_points_; // all landmarks + unordered_map keyframes_; // all key-frames + + Map() {} + + void insertKeyFrame( Frame::Ptr frame ); + void insertMapPoint( MapPoint::Ptr map_point ); +}; +} + +#endif // MAP_H diff --git a/vSLAM/ch9 project/0.4/include/myslam/mappoint.h b/vSLAM/ch9 project/0.4/include/myslam/mappoint.h new file mode 100644 index 00000000..3429b141 --- /dev/null +++ b/vSLAM/ch9 project/0.4/include/myslam/mappoint.h @@ -0,0 +1,67 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifndef MAPPOINT_H +#define MAPPOINT_H + +#include "myslam/common_include.h" + +namespace myslam +{ + +class Frame; +class MapPoint +{ +public: + typedef shared_ptr Ptr; + unsigned long id_; // ID + static unsigned long factory_id_; // factory id + bool good_; // wheter a good point + Vector3d pos_; // Position in world + Vector3d norm_; // Normal of viewing direction + Mat descriptor_; // Descriptor for matching + + list observed_frames_; // key-frames that can observe this point + + int matched_times_; // being an inliner in pose estimation + int visible_times_; // being visible in current frame + + MapPoint(); + MapPoint( + unsigned long id, + const Vector3d& position, + const Vector3d& norm, + Frame* frame=nullptr, + const Mat& descriptor=Mat() + ); + + inline cv::Point3f getPositionCV() const { + return cv::Point3f( pos_(0,0), pos_(1,0), pos_(2,0) ); + } + + static MapPoint::Ptr createMapPoint(); + static MapPoint::Ptr createMapPoint( + const Vector3d& pos_world, + const Vector3d& norm_, + const Mat& descriptor, + Frame* frame ); +}; +} + +#endif // MAPPOINT_H diff --git a/vSLAM/ch9 project/0.4/include/myslam/visual_odometry.h b/vSLAM/ch9 project/0.4/include/myslam/visual_odometry.h new file mode 100644 index 00000000..355fe56a --- /dev/null +++ b/vSLAM/ch9 project/0.4/include/myslam/visual_odometry.h @@ -0,0 +1,93 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifndef VISUALODOMETRY_H +#define VISUALODOMETRY_H + +#include "myslam/common_include.h" +#include "myslam/map.h" + +#include + +namespace myslam +{ +class VisualOdometry +{ +public: + typedef shared_ptr Ptr; + enum VOState { + INITIALIZING=-1, + OK=0, + LOST + }; + + VOState state_; // current VO status + Map::Ptr map_; // map with all frames and map points + + Frame::Ptr ref_; // reference key-frame + Frame::Ptr curr_; // current frame + + cv::Ptr orb_; // orb detector and computer + vector keypoints_curr_; // keypoints in current frame + Mat descriptors_curr_; // descriptor in current frame + + cv::FlannBasedMatcher matcher_flann_; // flann matcher + vector match_3dpts_; // matched 3d points + vector match_2dkp_index_; // matched 2d pixels (index of kp_curr) + + SE3 T_c_w_estimated_; // the estimated pose of current frame + int num_inliers_; // number of inlier features in icp + int num_lost_; // number of lost times + + // parameters + int num_of_features_; // number of features + double scale_factor_; // scale in image pyramid + int level_pyramid_; // number of pyramid levels + float match_ratio_; // ratio for selecting good matches + int max_num_lost_; // max number of continuous lost times + int min_inliers_; // minimum inliers + double key_frame_min_rot; // minimal rotation of two key-frames + double key_frame_min_trans; // minimal translation of two key-frames + double map_point_erase_ratio_; // remove map point ratio + +public: // functions + VisualOdometry(); + ~VisualOdometry(); + + bool addFrame( Frame::Ptr frame ); // add a new frame + +protected: + // inner operation + void extractKeyPoints(); + void computeDescriptors(); + void featureMatching(); + void poseEstimationPnP(); + void optimizeMap(); + + void addKeyFrame(); + void addMapPoints(); + bool checkEstimatedPose(); + bool checkKeyFrame(); + + double getViewAngle( Frame::Ptr frame, MapPoint::Ptr point ); + +}; +} + +#endif // VISUALODOMETRY_H diff --git a/vSLAM/ch9 project/0.4/lib/liblibmyslam.a b/vSLAM/ch9 project/0.4/lib/liblibmyslam.a new file mode 100644 index 00000000..46f62f98 Binary files /dev/null and b/vSLAM/ch9 project/0.4/lib/liblibmyslam.a differ diff --git a/vSLAM/ch9 project/0.4/lib/libmyslam.so b/vSLAM/ch9 project/0.4/lib/libmyslam.so new file mode 100755 index 00000000..d52d1750 Binary files /dev/null and b/vSLAM/ch9 project/0.4/lib/libmyslam.so differ diff --git a/vSLAM/ch9 project/0.4/src/CMakeLists.txt b/vSLAM/ch9 project/0.4/src/CMakeLists.txt new file mode 100644 index 00000000..07355f17 --- /dev/null +++ b/vSLAM/ch9 project/0.4/src/CMakeLists.txt @@ -0,0 +1,13 @@ +add_library( myslam SHARED + frame.cpp + mappoint.cpp + map.cpp + camera.cpp + config.cpp + g2o_types.cpp + visual_odometry.cpp +) + +target_link_libraries( myslam + ${THIRD_PARTY_LIBS} +) \ No newline at end of file diff --git a/vSLAM/ch9 project/0.4/src/camera.cpp b/vSLAM/ch9 project/0.4/src/camera.cpp new file mode 100644 index 00000000..d79d63eb --- /dev/null +++ b/vSLAM/ch9 project/0.4/src/camera.cpp @@ -0,0 +1,73 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "myslam/camera.h" +#include + +namespace myslam +{ + +Camera::Camera() +{ + fx_ = Config::get("camera.fx"); + fy_ = Config::get("camera.fy"); + cx_ = Config::get("camera.cx"); + cy_ = Config::get("camera.cy"); + depth_scale_ = Config::get("camera.depth_scale"); +} + +Vector3d Camera::world2camera ( const Vector3d& p_w, const SE3& T_c_w ) +{ + return T_c_w*p_w; +} + +Vector3d Camera::camera2world ( const Vector3d& p_c, const SE3& T_c_w ) +{ + return T_c_w.inverse() *p_c; +} + +Vector2d Camera::camera2pixel ( const Vector3d& p_c ) +{ + return Vector2d ( + fx_ * p_c ( 0,0 ) / p_c ( 2,0 ) + cx_, + fy_ * p_c ( 1,0 ) / p_c ( 2,0 ) + cy_ + ); +} + +Vector3d Camera::pixel2camera ( const Vector2d& p_p, double depth ) +{ + return Vector3d ( + ( p_p ( 0,0 )-cx_ ) *depth/fx_, + ( p_p ( 1,0 )-cy_ ) *depth/fy_, + depth + ); +} + +Vector2d Camera::world2pixel ( const Vector3d& p_w, const SE3& T_c_w ) +{ + return camera2pixel ( world2camera(p_w, T_c_w) ); +} + +Vector3d Camera::pixel2world ( const Vector2d& p_p, const SE3& T_c_w, double depth ) +{ + return camera2world ( pixel2camera ( p_p, depth ), T_c_w ); +} + + +} diff --git a/vSLAM/ch9 project/0.4/src/config.cpp b/vSLAM/ch9 project/0.4/src/config.cpp new file mode 100644 index 00000000..9817d8d5 --- /dev/null +++ b/vSLAM/ch9 project/0.4/src/config.cpp @@ -0,0 +1,46 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "myslam/config.h" + +namespace myslam +{ + +void Config::setParameterFile( const std::string& filename ) +{ + if ( config_ == nullptr ) + config_ = shared_ptr(new Config); + config_->file_ = cv::FileStorage( filename.c_str(), cv::FileStorage::READ ); + if ( config_->file_.isOpened() == false ) + { + std::cerr<<"parameter file "<file_.release(); + return; + } +} + +Config::~Config() +{ + if ( file_.isOpened() ) + file_.release(); +} + +shared_ptr Config::config_ = nullptr; + +} diff --git a/vSLAM/ch9 project/0.4/src/frame.cpp b/vSLAM/ch9 project/0.4/src/frame.cpp new file mode 100644 index 00000000..c0c118c9 --- /dev/null +++ b/vSLAM/ch9 project/0.4/src/frame.cpp @@ -0,0 +1,96 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "myslam/frame.h" + +namespace myslam +{ +Frame::Frame() +: id_(-1), time_stamp_(-1), camera_(nullptr), is_key_frame_(false) +{ + +} + +Frame::Frame ( long id, double time_stamp, SE3 T_c_w, Camera::Ptr camera, Mat color, Mat depth ) +: id_(id), time_stamp_(time_stamp), T_c_w_(T_c_w), camera_(camera), color_(color), depth_(depth), is_key_frame_(false) +{ + +} + +Frame::~Frame() +{ + +} + +Frame::Ptr Frame::createFrame() +{ + static long factory_id = 0; + return Frame::Ptr( new Frame(factory_id++) ); +} + +double Frame::findDepth ( const cv::KeyPoint& kp ) +{ + int x = cvRound(kp.pt.x); + int y = cvRound(kp.pt.y); + ushort d = depth_.ptr(y)[x]; + if ( d!=0 ) + { + return double(d)/camera_->depth_scale_; + } + else + { + // check the nearby points + int dx[4] = {-1,0,1,0}; + int dy[4] = {0,-1,0,1}; + for ( int i=0; i<4; i++ ) + { + d = depth_.ptr( y+dy[i] )[x+dx[i]]; + if ( d!=0 ) + { + return double(d)/camera_->depth_scale_; + } + } + } + return -1.0; +} + +void Frame::setPose ( const SE3& T_c_w ) +{ + T_c_w_ = T_c_w; +} + + +Vector3d Frame::getCamCenter() const +{ + return T_c_w_.inverse().translation(); +} + +bool Frame::isInFrame ( const Vector3d& pt_world ) +{ + Vector3d p_cam = camera_->world2camera( pt_world, T_c_w_ ); + // cout<<"P_cam = "<world2pixel( pt_world, T_c_w_ ); + // cout<<"P_pixel = "<0 && pixel(1,0)>0 + && pixel(0,0) ( _vertices[0] ); + const g2o::VertexSE3Expmap* pose = static_cast ( _vertices[1] ); + _error = _measurement - pose->estimate().map ( point->estimate() ); +} + +void EdgeProjectXYZRGBD::linearizeOplus() +{ + g2o::VertexSE3Expmap* pose = static_cast ( _vertices[1] ); + g2o::SE3Quat T ( pose->estimate() ); + g2o::VertexSBAPointXYZ* point = static_cast ( _vertices[0] ); + Eigen::Vector3d xyz = point->estimate(); + Eigen::Vector3d xyz_trans = T.map ( xyz ); + double x = xyz_trans[0]; + double y = xyz_trans[1]; + double z = xyz_trans[2]; + + _jacobianOplusXi = - T.rotation().toRotationMatrix(); + + _jacobianOplusXj ( 0,0 ) = 0; + _jacobianOplusXj ( 0,1 ) = -z; + _jacobianOplusXj ( 0,2 ) = y; + _jacobianOplusXj ( 0,3 ) = -1; + _jacobianOplusXj ( 0,4 ) = 0; + _jacobianOplusXj ( 0,5 ) = 0; + + _jacobianOplusXj ( 1,0 ) = z; + _jacobianOplusXj ( 1,1 ) = 0; + _jacobianOplusXj ( 1,2 ) = -x; + _jacobianOplusXj ( 1,3 ) = 0; + _jacobianOplusXj ( 1,4 ) = -1; + _jacobianOplusXj ( 1,5 ) = 0; + + _jacobianOplusXj ( 2,0 ) = -y; + _jacobianOplusXj ( 2,1 ) = x; + _jacobianOplusXj ( 2,2 ) = 0; + _jacobianOplusXj ( 2,3 ) = 0; + _jacobianOplusXj ( 2,4 ) = 0; + _jacobianOplusXj ( 2,5 ) = -1; +} + +void EdgeProjectXYZRGBDPoseOnly::computeError() +{ + const g2o::VertexSE3Expmap* pose = static_cast ( _vertices[0] ); + _error = _measurement - pose->estimate().map ( point_ ); +} + +void EdgeProjectXYZRGBDPoseOnly::linearizeOplus() +{ + g2o::VertexSE3Expmap* pose = static_cast ( _vertices[0] ); + g2o::SE3Quat T ( pose->estimate() ); + Vector3d xyz_trans = T.map ( point_ ); + double x = xyz_trans[0]; + double y = xyz_trans[1]; + double z = xyz_trans[2]; + + _jacobianOplusXi ( 0,0 ) = 0; + _jacobianOplusXi ( 0,1 ) = -z; + _jacobianOplusXi ( 0,2 ) = y; + _jacobianOplusXi ( 0,3 ) = -1; + _jacobianOplusXi ( 0,4 ) = 0; + _jacobianOplusXi ( 0,5 ) = 0; + + _jacobianOplusXi ( 1,0 ) = z; + _jacobianOplusXi ( 1,1 ) = 0; + _jacobianOplusXi ( 1,2 ) = -x; + _jacobianOplusXi ( 1,3 ) = 0; + _jacobianOplusXi ( 1,4 ) = -1; + _jacobianOplusXi ( 1,5 ) = 0; + + _jacobianOplusXi ( 2,0 ) = -y; + _jacobianOplusXi ( 2,1 ) = x; + _jacobianOplusXi ( 2,2 ) = 0; + _jacobianOplusXi ( 2,3 ) = 0; + _jacobianOplusXi ( 2,4 ) = 0; + _jacobianOplusXi ( 2,5 ) = -1; +} + +void EdgeProjectXYZ2UVPoseOnly::computeError() +{ + const g2o::VertexSE3Expmap* pose = static_cast ( _vertices[0] ); + _error = _measurement - camera_->camera2pixel ( + pose->estimate().map(point_) ); +} + +void EdgeProjectXYZ2UVPoseOnly::linearizeOplus() +{ + g2o::VertexSE3Expmap* pose = static_cast ( _vertices[0] ); + g2o::SE3Quat T ( pose->estimate() ); + Vector3d xyz_trans = T.map ( point_ ); + double x = xyz_trans[0]; + double y = xyz_trans[1]; + double z = xyz_trans[2]; + double z_2 = z*z; + + _jacobianOplusXi ( 0,0 ) = x*y/z_2 *camera_->fx_; + _jacobianOplusXi ( 0,1 ) = - ( 1+ ( x*x/z_2 ) ) *camera_->fx_; + _jacobianOplusXi ( 0,2 ) = y/z * camera_->fx_; + _jacobianOplusXi ( 0,3 ) = -1./z * camera_->fx_; + _jacobianOplusXi ( 0,4 ) = 0; + _jacobianOplusXi ( 0,5 ) = x/z_2 * camera_->fx_; + + _jacobianOplusXi ( 1,0 ) = ( 1+y*y/z_2 ) *camera_->fy_; + _jacobianOplusXi ( 1,1 ) = -x*y/z_2 *camera_->fy_; + _jacobianOplusXi ( 1,2 ) = -x/z *camera_->fy_; + _jacobianOplusXi ( 1,3 ) = 0; + _jacobianOplusXi ( 1,4 ) = -1./z *camera_->fy_; + _jacobianOplusXi ( 1,5 ) = y/z_2 *camera_->fy_; +} + + +} diff --git a/vSLAM/ch9 project/0.4/src/map.cpp b/vSLAM/ch9 project/0.4/src/map.cpp new file mode 100644 index 00000000..21faca53 --- /dev/null +++ b/vSLAM/ch9 project/0.4/src/map.cpp @@ -0,0 +1,51 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "myslam/map.h" + +namespace myslam +{ + +void Map::insertKeyFrame ( Frame::Ptr frame ) +{ + cout<<"Key frame size = "<id_) == keyframes_.end() ) + { + keyframes_.insert( make_pair(frame->id_, frame) ); + } + else + { + keyframes_[ frame->id_ ] = frame; + } +} + +void Map::insertMapPoint ( MapPoint::Ptr map_point ) +{ + if ( map_points_.find(map_point->id_) == map_points_.end() ) + { + map_points_.insert( make_pair(map_point->id_, map_point) ); + } + else + { + map_points_[map_point->id_] = map_point; + } +} + + +} diff --git a/vSLAM/ch9 project/0.4/src/mappoint.cpp b/vSLAM/ch9 project/0.4/src/mappoint.cpp new file mode 100644 index 00000000..a89a18bf --- /dev/null +++ b/vSLAM/ch9 project/0.4/src/mappoint.cpp @@ -0,0 +1,58 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "myslam/common_include.h" +#include "myslam/mappoint.h" + +namespace myslam +{ + +MapPoint::MapPoint() +: id_(-1), pos_(Vector3d(0,0,0)), norm_(Vector3d(0,0,0)), good_(true), visible_times_(0), matched_times_(0) +{ + +} + +MapPoint::MapPoint ( long unsigned int id, const Vector3d& position, const Vector3d& norm, Frame* frame, const Mat& descriptor ) +: id_(id), pos_(position), norm_(norm), good_(true), visible_times_(1), matched_times_(1), descriptor_(descriptor) +{ + observed_frames_.push_back(frame); +} + +MapPoint::Ptr MapPoint::createMapPoint() +{ + return MapPoint::Ptr( + new MapPoint( factory_id_++, Vector3d(0,0,0), Vector3d(0,0,0) ) + ); +} + +MapPoint::Ptr MapPoint::createMapPoint ( + const Vector3d& pos_world, + const Vector3d& norm, + const Mat& descriptor, + Frame* frame ) +{ + return MapPoint::Ptr( + new MapPoint( factory_id_++, pos_world, norm, frame, descriptor ) + ); +} + +unsigned long MapPoint::factory_id_ = 0; + +} diff --git a/vSLAM/ch9 project/0.4/src/visual_odometry.cpp b/vSLAM/ch9 project/0.4/src/visual_odometry.cpp new file mode 100644 index 00000000..9d03b691 --- /dev/null +++ b/vSLAM/ch9 project/0.4/src/visual_odometry.cpp @@ -0,0 +1,367 @@ +/* + * + * Copyright (C) 2016 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include +#include +#include +#include +#include + +#include "myslam/config.h" +#include "myslam/visual_odometry.h" +#include "myslam/g2o_types.h" + +namespace myslam +{ + +VisualOdometry::VisualOdometry() : + state_ ( INITIALIZING ), ref_ ( nullptr ), curr_ ( nullptr ), map_ ( new Map ), num_lost_ ( 0 ), num_inliers_ ( 0 ), matcher_flann_ ( new cv::flann::LshIndexParams ( 5,10,2 ) ) +{ + num_of_features_ = Config::get ( "number_of_features" ); + scale_factor_ = Config::get ( "scale_factor" ); + level_pyramid_ = Config::get ( "level_pyramid" ); + match_ratio_ = Config::get ( "match_ratio" ); + max_num_lost_ = Config::get ( "max_num_lost" ); + min_inliers_ = Config::get ( "min_inliers" ); + key_frame_min_rot = Config::get ( "keyframe_rotation" ); + key_frame_min_trans = Config::get ( "keyframe_translation" ); + map_point_erase_ratio_ = Config::get ( "map_point_erase_ratio" ); + orb_ = cv::ORB::create ( num_of_features_, scale_factor_, level_pyramid_ ); +} + +VisualOdometry::~VisualOdometry() +{ + +} + +bool VisualOdometry::addFrame ( Frame::Ptr frame ) +{ + switch ( state_ ) + { + case INITIALIZING: + { + state_ = OK; + curr_ = ref_ = frame; + // extract features from first frame and add them into map + extractKeyPoints(); + computeDescriptors(); + addKeyFrame(); // the first frame is a key-frame + break; + } + case OK: + { + curr_ = frame; + curr_->T_c_w_ = ref_->T_c_w_; + extractKeyPoints(); + computeDescriptors(); + featureMatching(); + poseEstimationPnP(); + if ( checkEstimatedPose() == true ) // a good estimation + { + curr_->T_c_w_ = T_c_w_estimated_; + optimizeMap(); + num_lost_ = 0; + if ( checkKeyFrame() == true ) // is a key-frame + { + addKeyFrame(); + } + } + else // bad estimation due to various reasons + { + num_lost_++; + if ( num_lost_ > max_num_lost_ ) + { + state_ = LOST; + } + return false; + } + break; + } + case LOST: + { + cout<<"vo has lost."<detect ( curr_->color_, keypoints_curr_ ); + cout<<"extract keypoints cost time: "<compute ( curr_->color_, keypoints_curr_, descriptors_curr_ ); + cout<<"descriptor computation cost time: "< matches; + // select the candidates in map + Mat desp_map; + vector candidate; + for ( auto& allpoints: map_->map_points_ ) + { + MapPoint::Ptr& p = allpoints.second; + // check if p in curr frame image + if ( curr_->isInFrame(p->pos_) ) + { + // add to candidate + p->visible_times_++; + candidate.push_back( p ); + desp_map.push_back( p->descriptor_ ); + } + } + + matcher_flann_.match ( desp_map, descriptors_curr_, matches ); + // select the best matches + float min_dis = std::min_element ( + matches.begin(), matches.end(), + [] ( const cv::DMatch& m1, const cv::DMatch& m2 ) + { + return m1.distance < m2.distance; + } )->distance; + + match_3dpts_.clear(); + match_2dkp_index_.clear(); + for ( cv::DMatch& m : matches ) + { + if ( m.distance < max ( min_dis*match_ratio_, 30.0 ) ) + { + match_3dpts_.push_back( candidate[m.queryIdx] ); + match_2dkp_index_.push_back( m.trainIdx ); + } + } + cout<<"good matches: "< pts3d; + vector pts2d; + + for ( int index:match_2dkp_index_ ) + { + pts2d.push_back ( keypoints_curr_[index].pt ); + } + for ( MapPoint::Ptr pt:match_3dpts_ ) + { + pts3d.push_back( pt->getPositionCV() ); + } + + Mat K = ( cv::Mat_ ( 3,3 ) << + ref_->camera_->fx_, 0, ref_->camera_->cx_, + 0, ref_->camera_->fy_, ref_->camera_->cy_, + 0,0,1 + ); + Mat rvec, tvec, inliers; + cv::solvePnPRansac ( pts3d, pts2d, K, Mat(), rvec, tvec, false, 100, 4.0, 0.99, inliers ); + num_inliers_ = inliers.rows; + cout<<"pnp inliers: "< ( 0,0 ), rvec.at ( 1,0 ), rvec.at ( 2,0 ) ), + Vector3d ( tvec.at ( 0,0 ), tvec.at ( 1,0 ), tvec.at ( 2,0 ) ) + ); + + // using bundle adjustment to optimize the pose + typedef g2o::BlockSolver> Block; + Block::LinearSolverType* linearSolver = new g2o::LinearSolverDense(); + Block* solver_ptr = new Block ( linearSolver ); + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg ( solver_ptr ); + g2o::SparseOptimizer optimizer; + optimizer.setAlgorithm ( solver ); + + g2o::VertexSE3Expmap* pose = new g2o::VertexSE3Expmap(); + pose->setId ( 0 ); + pose->setEstimate ( g2o::SE3Quat ( + T_c_w_estimated_.rotation_matrix(), T_c_w_estimated_.translation() + )); + optimizer.addVertex ( pose ); + + // edges + for ( int i=0; i ( i,0 ); + // 3D -> 2D projection + EdgeProjectXYZ2UVPoseOnly* edge = new EdgeProjectXYZ2UVPoseOnly(); + edge->setId ( i ); + edge->setVertex ( 0, pose ); + edge->camera_ = curr_->camera_.get(); + edge->point_ = Vector3d ( pts3d[index].x, pts3d[index].y, pts3d[index].z ); + edge->setMeasurement ( Vector2d ( pts2d[index].x, pts2d[index].y ) ); + edge->setInformation ( Eigen::Matrix2d::Identity() ); + optimizer.addEdge ( edge ); + // set the inlier map points + match_3dpts_[index]->matched_times_++; + } + + optimizer.initializeOptimization(); + optimizer.optimize ( 10 ); + + T_c_w_estimated_ = SE3 ( + pose->estimate().rotation(), + pose->estimate().translation() + ); + + cout<<"T_c_w_estimated_: "<T_c_w_ * T_c_w_estimated_.inverse(); + Sophus::Vector6d d = T_r_c.log(); + if ( d.norm() > 5.0 ) + { + cout<<"reject because motion is too large: "<T_c_w_ * T_c_w_estimated_.inverse(); + Sophus::Vector6d d = T_r_c.log(); + Vector3d trans = d.head<3>(); + Vector3d rot = d.tail<3>(); + if ( rot.norm() >key_frame_min_rot || trans.norm() >key_frame_min_trans ) + return true; + return false; +} + +void VisualOdometry::addKeyFrame() +{ + if ( map_->keyframes_.empty() ) + { + // first key-frame, add all 3d points into map + for ( size_t i=0; ifindDepth ( keypoints_curr_[i] ); + if ( d < 0 ) + continue; + Vector3d p_world = ref_->camera_->pixel2world ( + Vector2d ( keypoints_curr_[i].pt.x, keypoints_curr_[i].pt.y ), curr_->T_c_w_, d + ); + Vector3d n = p_world - ref_->getCamCenter(); + n.normalize(); + MapPoint::Ptr map_point = MapPoint::createMapPoint( + p_world, n, descriptors_curr_.row(i).clone(), curr_.get() + ); + map_->insertMapPoint( map_point ); + } + } + + map_->insertKeyFrame ( curr_ ); + ref_ = curr_; +} + +void VisualOdometry::addMapPoints() +{ + // add the new map points into map + vector matched(keypoints_curr_.size(), false); + for ( int index:match_2dkp_index_ ) + matched[index] = true; + for ( int i=0; ifindDepth ( keypoints_curr_[i] ); + if ( d<0 ) + continue; + Vector3d p_world = ref_->camera_->pixel2world ( + Vector2d ( keypoints_curr_[i].pt.x, keypoints_curr_[i].pt.y ), + curr_->T_c_w_, d + ); + Vector3d n = p_world - ref_->getCamCenter(); + n.normalize(); + MapPoint::Ptr map_point = MapPoint::createMapPoint( + p_world, n, descriptors_curr_.row(i).clone(), curr_.get() + ); + map_->insertMapPoint( map_point ); + } +} + +void VisualOdometry::optimizeMap() +{ + // remove the hardly seen and no visible points + for ( auto iter = map_->map_points_.begin(); iter != map_->map_points_.end(); ) + { + if ( !curr_->isInFrame(iter->second->pos_) ) + { + iter = map_->map_points_.erase(iter); + continue; + } + float match_ratio = float(iter->second->matched_times_)/iter->second->visible_times_; + if ( match_ratio < map_point_erase_ratio_ ) + { + iter = map_->map_points_.erase(iter); + continue; + } + + double angle = getViewAngle( curr_, iter->second ); + if ( angle > M_PI/6. ) + { + iter = map_->map_points_.erase(iter); + continue; + } + if ( iter->second->good_ == false ) + { + // TODO try triangulate this map point + } + iter++; + } + + if ( match_2dkp_index_.size()<100 ) + addMapPoints(); + if ( map_->map_points_.size() > 1000 ) + { + // TODO map is too large, remove some one + map_point_erase_ratio_ += 0.05; + } + else + map_point_erase_ratio_ = 0.1; + cout<<"map points: "<map_points_.size()<pos_ - frame->getCamCenter(); + n.normalize(); + return acos( n.transpose()*point->norm_ ); +} + + +} diff --git a/vSLAM/ch9 project/0.4/test/CMakeLists.txt b/vSLAM/ch9 project/0.4/test/CMakeLists.txt new file mode 100644 index 00000000..241c4599 --- /dev/null +++ b/vSLAM/ch9 project/0.4/test/CMakeLists.txt @@ -0,0 +1,2 @@ +add_executable( run_vo run_vo.cpp ) +target_link_libraries( run_vo myslam ) \ No newline at end of file diff --git a/vSLAM/ch9 project/0.4/test/run_vo.cpp b/vSLAM/ch9 project/0.4/test/run_vo.cpp new file mode 100644 index 00000000..5fec8fed --- /dev/null +++ b/vSLAM/ch9 project/0.4/test/run_vo.cpp @@ -0,0 +1,113 @@ +// -------------- test the visual odometry ------------- +#include +#include +#include +#include +#include +#include + +#include "myslam/config.h" +#include "myslam/visual_odometry.h" + +int main ( int argc, char** argv ) +{ + if ( argc != 2 ) + { + cout<<"usage: run_vo parameter_file"< ( "dataset_dir" );//数据集 + cout<<"dataset: "< rgb_files, depth_files;//数据集彩色图 深度图文件路径 + vector rgb_times, depth_times;//对于时间 + while ( !fin.eof() ) + { + string rgb_time, rgb_file, depth_time, depth_file; + fin>>rgb_time>>rgb_file>>depth_time>>depth_file; + rgb_times.push_back ( atof ( rgb_time.c_str() ) ); + depth_times.push_back ( atof ( depth_time.c_str() ) ); + rgb_files.push_back ( dataset_dir+"/"+rgb_file ); + depth_files.push_back ( dataset_dir+"/"+depth_file ); + + if ( fin.good() == false ) + break; + } + + myslam::Camera::Ptr camera ( new myslam::Camera );//相机模型 + + // visualization 相机位姿 可视化 + cv::viz::Viz3d vis ( "Visual Odometry" ); + cv::viz::WCoordinateSystem world_coor ( 1.0 ), camera_coor ( 0.5 ); + cv::Point3d cam_pos ( 0, -1.0, -1.0 ), cam_focal_point ( 0,0,0 ), cam_y_dir ( 0,1,0 ); + cv::Affine3d cam_pose = cv::viz::makeCameraPose ( cam_pos, cam_focal_point, cam_y_dir ); + vis.setViewerPose ( cam_pose ); + //可视化图形初始化 颜色 大小等 + world_coor.setRenderingProperty ( cv::viz::LINE_WIDTH, 2.0 ); + camera_coor.setRenderingProperty ( cv::viz::LINE_WIDTH, 1.0 ); + vis.showWidget ( "World", world_coor ); + vis.showWidget ( "Camera", camera_coor ); + + cout<<"read total "<camera_ = camera;//相机模型 + pFrame->color_ = color;//彩色图 + pFrame->depth_ = depth;//深度图 + pFrame->time_stamp_ = rgb_times[i];//时间戳 + + boost::timer timer;//算法时间记录 + vo->addFrame ( pFrame );//视觉里程计 添加 + cout<<"VO costs time: "<state_ == myslam::VisualOdometry::LOST ) + break; + SE3 Twc = pFrame->T_c_w_.inverse();//相机位姿 + + // show the map and the camera pose + cv::Affine3d M (//相机位姿信息 + cv::Affine3d::Mat3 ( + Twc.rotation_matrix() ( 0,0 ), Twc.rotation_matrix() ( 0,1 ), Twc.rotation_matrix() ( 0,2 ), + Twc.rotation_matrix() ( 1,0 ), Twc.rotation_matrix() ( 1,1 ), Twc.rotation_matrix() ( 1,2 ), + Twc.rotation_matrix() ( 2,0 ), Twc.rotation_matrix() ( 2,1 ), Twc.rotation_matrix() ( 2,2 ) + ), + cv::Affine3d::Vec3 ( + Twc.translation() ( 0,0 ), Twc.translation() ( 1,0 ), Twc.translation() ( 2,0 ) + ) + ); + + // 显示关键点 + Mat img_show = color.clone();//复制图形 + for ( auto& pt:vo->map_->map_points_ )//每个关键点 + { + myslam::MapPoint::Ptr p = pt.second; + Vector2d pixel = pFrame->camera_->world2pixel ( p->pos_, pFrame->T_c_w_ );//世界坐标系中的点转化到 图像像素坐标系 + cv::circle ( img_show, cv::Point2f ( pixel ( 0,0 ),pixel ( 1,0 ) ), 5, cv::Scalar ( 0,255,0 ), 2 );//在每个关键点处 画圆 + } + + cv::imshow ( "image", img_show );//显示图片 + cv::waitKey ( 0 ); + //cv::waitKey ( 1 ); + vis.setWidgetPose ( "Camera", M );//显示相机位姿 + vis.spinOnce ( 1, false ); + cout<