$search
00001 00005 #ifndef _THERMALSFM_SBA_H_ 00006 #define _THERMALSFM_SBA_H_ 00007 00008 #include "general_resources.hpp" 00009 #include "opencv_resources.hpp" 00010 #include "ros_resources.hpp" 00011 #include "reconstruction.hpp" 00012 #include "keyframes.hpp" 00013 #include "tracks.hpp" 00014 // #include <ros/ros.h> 00015 #include <sba/sba.h> 00016 #include <sba/visualization.h> 00017 00018 // For random seed. 00019 #include <time.h> 00020 //#include <visualization_msgs/Marker.h> 00021 00022 00023 00024 void rescaleSBA(SysSBA& sba, unsigned int idx1, unsigned int idx2); 00025 00026 void findRelevantIndices(vector<featureTrack>& tracks, vector<unsigned int>& triangulated, vector<unsigned int>& untriangulated, unsigned int last_index, unsigned int new_index); 00027 00028 void optimizeFullSystem(vector<featureTrack>& tracks, cameraParameters& camData, Mat *cameras, unsigned int last_index); 00029 00030 void findIntermediatePoses(vector<featureTrack>& tracks, cameraParameters& camData, Mat *cameras, unsigned int image_idx_1, unsigned int image_idx_2, bool fixBothEnds = true); 00031 00032 double getFeatureMotion(vector<featureTrack>& tracks, vector<unsigned int>& indices, unsigned int idx_1, unsigned int idx_2); 00033 00034 //void createSupersys(SysSBA &sba, vector<featureTrack>& tracks, unsigned int total_cameras); 00035 00036 void assignFullSystem(SysSBA &sba, vector<featureTrack>& tracks, cameraParameters& camData, Mat *cameras, unsigned int start_index, unsigned int finish_index, bool dummy = false); 00037 00038 void assignPartialSystem(SysSBA &sba, vector<featureTrack>& tracks, cameraParameters& camData, Mat *cameras, vector<unsigned int>& indices, bool assignProjections = true); 00039 00040 bool reconstructFreshSubsequencePair(vector<featureTrack>& tracks, vector<Point3d>& ptCloud, vector<unsigned int>& triangulatedIndices, Mat& real_C0, Mat& real_C1, cameraParameters camData, int idx1, int idx2); 00041 00042 void subselectPoints(const vector<Point2f>& src1, vector<Point2f>& dst1, const vector<Point2f>& src2, vector<Point2f>& dst2); 00043 00044 int estimatePoseBetweenCameras(cameraParameters& camData, vector<Point2f>& pts1, vector<Point2f>& pts2, Mat& C); 00045 00046 double optimizeSystem(SysSBA &sba, double err = 1e-4, int iterations = 100); 00047 00048 double twoViewBundleAdjustment(cameraParameters cam_data, Mat& cam1, Mat& cam2, vector<Point3d>& cloud, vector<Point2f>& pts1, vector<Point2f>& pts2, int iterations = 10); 00049 00050 void initializeFrameCamera(frame_common::CamParams& cam_params, const Mat& newCamMat, int& maxx, int& maxy, const Size& cameraSize); 00051 00052 void drawGraph2(const SysSBA &sba, const ros::Publisher &camera_pub, const ros::Publisher &point_pub, const ros::Publisher &path_pub, int decimation = 1, int bicolor = 0, double scale = 0.1); 00053 00054 void extractPointCloud(const SysSBA &sba, pcl::PointCloud<pcl::PointXYZ>& point_cloud); 00055 00056 void extractCameras(const SysSBA &sba, visualization_msgs::MarkerArray& cameraArray, visualization_msgs::Marker& marker_path); 00057 00058 void addPointsToSBA(SysSBA& sba, vector<Point3d>& cloud); 00059 00060 void addProjectionsToSBA(SysSBA& sba, vector<Point2f>& loc, int idx); 00061 00062 double optimizeKeyframePair(vector<featureTrack>& tracks, cameraParameters& camData, int idx1, int idx2, Mat *cameras); 00063 00064 double testKeyframePair(vector<featureTrack>& tracks, cameraParameters& camData, double *scorecard[], int idx1, int idx2, double *scores, Mat& pose, bool evaluate = false, bool debug = false); 00065 00066 void addProjectionToSBA(SysSBA& sba, Point2f& loc, unsigned int trackNo, unsigned int camNo); 00067 00068 void removePoorTracks(vector<featureTrack>& tracks, cameraParameters& camData, Mat *cameras, unsigned int start_cam, unsigned int finish_cam); 00069 00070 double keyframeBundleAdjustment(cameraParameters& camData, vector<featureTrack>& tracks, Mat *cameras, vector<unsigned int>& indices, unsigned int iterations = 100, bool allFree = false, bool allFixedExceptLast = false, unsigned fixed_cams = 0); 00071 00072 double keyframeBundleAdjustment(cameraParameters& camData, vector<featureTrack>& tracks, keyframeStore& kf_store, Mat *cameras, unsigned int kfIndex, unsigned int iterations = 100); 00073 00074 void getActiveCameras(Mat *C, vector<unsigned int>& indices, unsigned int min_index, unsigned int max_index); 00075 00076 void getActiveTracks(vector<featureTrack>& tracks, vector<unsigned int>& cameras, vector<unsigned int>& indices); 00077 void assignSystem(SysSBA &sba, vector<featureTrack>& tracks, cameraParameters& camData, Mat *cameras, vector<unsigned int>& camera_indices, vector<unsigned int>& track_indices); 00078 void retrieveSystem(SysSBA &sba, vector<featureTrack>& tracks, cameraParameters& camData, Mat *cameras, vector<unsigned int>& camera_indices, vector<unsigned int>& track_indices); 00079 00080 void retrieveFullSystem(SysSBA& sys, Mat *C, vector<featureTrack>& tracks, unsigned int start_cam, unsigned int final_cam); 00081 00082 double adjustFullSystem(vector<featureTrack>& tracks, cameraParameters& camData, Mat *cameras, unsigned int min_index, unsigned int max_index, unsigned int its = 1); 00083 00084 void retrievePartialSystem(SysSBA& sys, Mat *C, vector<featureTrack>& tracks, vector<unsigned int>& indices); 00085 // SBA_BLOCK_JACOBIAN_PCG 3 00086 // SBA_DENSE_CHOLESKY 0 00087 // SBA_GRADIENT 2 00088 // SBA_SPARSE_CHOLESKY 1 00089 00090 void renormalizeSBA(SysSBA& sba, Point3d& desiredCenter); 00091 00092 void findCentroid(SysSBA& sba, Point3d& centroid, Point3d& stdDeviation); 00093 00094 void copySys(const SysSBA& src, SysSBA& dst); 00095 00096 double optimizeSubsystem(cameraParameters& camData, Mat *C, vector<unsigned int>& c_i, vector<featureTrack>& tracks, vector<unsigned int>& t_i, unsigned int iterations = 100); 00097 00098 void finishTracks(vector<featureTrack>& tracks, vector<Point2f>& pts, double retainProp = 0.80, unsigned int maxOccurrences = 0); 00099 #endif