$search
00001 00005 #ifndef _THERMALVIS_MONOSLAM_H_ 00006 #define _THERMALVIS_MONOSLAM_H_ 00007 00008 #include "general_resources.hpp" 00009 #include "ros_resources.hpp" 00010 #include "opencv_resources.hpp" 00011 #include "pcl_resources.hpp" 00012 00013 #include <cv_bridge/CvBridge.h> 00014 00015 #include "improc.hpp" 00016 #include "video.hpp" 00017 #include "features.hpp" 00018 #include "reconstruction.hpp" 00019 #include "sba.hpp" 00020 #include "keyframes.hpp" 00021 #include "geometry.hpp" 00022 00023 #include "feature_tracks.h" 00024 00025 #include "monoslamConfig.h" 00026 00027 typedef dynamic_reconfigure::Server < thermalvis::monoslamConfig > Server; 00028 00029 // Drawing 00030 #define DEFAULT_DRAWGRAPH_DECIMATION 1 00031 #define DEFAULT_DRAWGRAPH_BICOLOR 0 00032 00033 // Hard Limits 00034 #define MAX_FRAMES 1000 00035 #define MAX_TRACKS 10000 00036 #define SBA_MEMORY 134217728 00037 #define MAX_SEGMENTS 16 00038 #define INITIALIZATION_SCORING_PARAMETERS 5 00039 00040 typedef pcl::PointCloud<pcl::PointXYZ> PointCloud; 00041 00042 const char __PROGRAM__[] = "THERMALVIS_MONOSLAM"; 00043 00044 bool wantsToShutdown = false; 00045 void mySigintHandler(int sig); 00046 00048 struct slamData { 00049 00050 string stream; 00051 00052 double motionThreshold; 00053 int adjustmentFrames; 00054 int flowback; 00055 double minStartupScore; 00056 cameraParameters cameraData; 00057 bool debugMode; 00058 bool obtainStartingData(ros::NodeHandle& nh); 00059 00060 double dataTimeout; 00061 00062 int keyframeSpacing; 00063 00064 int maxGuides; 00065 int maxKeyframeSeparation; 00066 00067 int framesForTriangulation; 00068 00069 int timeSpacing; 00070 00071 int minTrackedFeatures; 00072 00073 int min3dPtsForPnP; 00074 00075 int maxInitializationFrames; 00076 00077 00078 double minGeometryScore; 00079 double minKeyframeScore; 00080 00081 double requiredTrackFrac; 00082 00083 int camerasPerSys; 00084 00085 bool timeDebug; 00086 00087 bool logErrors; 00088 00089 int maxTestsPerFrame; 00090 00091 int initialStructureIterations, poseEstimateIterations, fullSystemIterations, subsequenceIterations, keyframeIterations; 00092 00093 bool keyframeEvaluationMode; 00094 00095 int minStartingSeparation, maxStartingSeparation; 00096 00097 string read_addr, evaluationFile, errorFile, initializationScorecard; 00098 00099 }; 00100 00102 struct timeAnalyzer { 00103 00104 int cycles; 00105 double vals[1024]; 00106 double average; 00107 double sigma; 00108 00109 struct timeval cycle_timer; 00110 00111 timeAnalyzer(); 00112 void calcParameters(); 00113 void startRecording(); 00114 void stopRecording(); 00115 00116 }; 00117 00119 class slamNode { 00120 private: 00121 00122 int decimation; 00123 int bicolor; 00124 00125 bool isTracking; 00126 00127 bool f1; 00128 00129 bool evaluationCompleted; 00130 00131 unsigned int baseConnectionNum; 00132 00133 double **scorecardParams; 00134 00135 slamData configData; 00136 00137 ofstream evaluationStream; 00138 00139 unsigned int nextFrame; 00140 00141 unsigned int putativelyEstimatedFrames; 00142 00143 Mat eye4; 00144 00145 bool repetitionNoted; 00146 00147 ofstream error_file; 00148 char error_filename[256]; 00149 00150 ros::Subscriber tracks_sub; 00151 ros::Subscriber info_sub; 00152 00153 SysSBA sys, display_sys; 00154 ros::Publisher path_pub; 00155 ros::Publisher camera_pub; 00156 ros::Publisher points_pub; 00157 00158 ros::Timer timer; 00159 00160 bool firstIteration; 00161 00162 Mat blank; 00163 00164 bool structureValid, structureFormed; 00165 00166 int latestFrame; 00167 00168 bool infoProcessed; 00169 00170 struct timeval cycle_timer; 00171 double elapsedTime; 00172 00173 double distanceConstraint; 00174 00175 vector<featureTrack> featureTrackVector; 00176 00177 Point3d cloudCentroid[MAX_SEGMENTS], cloudStdDeviation[MAX_SEGMENTS]; 00178 keyframeStore keyframe_store; 00179 Mat F_arr[MAX_FRAMES], H_arr[MAX_FRAMES]; 00180 00181 Mat ACM[MAX_FRAMES], ACM2[MAX_FRAMES]; 00182 00183 Mat keyframeTestScores, keyframeTestFlags; 00184 00185 char nodeName[256]; 00186 00187 ros::Publisher pose_pub; 00188 char pose_pub_name[256]; 00189 00190 geometry_msgs::PoseStamped currentPose; 00191 00192 int currentPoseIndex; 00193 00194 double minimumKeyframeScore; 00195 00196 vector<unsigned int> framesReceived; 00197 00198 unsigned int lastBasePose; 00199 00200 unsigned int startingTracksCount; 00201 00202 timeAnalyzer trackHandlingTime; 00203 timeAnalyzer triangulationTime; 00204 timeAnalyzer poseEstimationTime; 00205 timeAnalyzer bundleAdjustmentTime; 00206 00207 // Thread-protection 00208 boost::mutex cam_mutex; 00209 boost::mutex tracks_mutex; 00210 boost::mutex keyframes_mutex; 00211 boost::mutex main_mutex; 00212 00213 dynamic_reconfigure::Server<thermalvis::monoslamConfig> server; 00214 dynamic_reconfigure::Server<thermalvis::monoslamConfig>::CallbackType f; 00215 00216 public: 00217 00218 slamNode(ros::NodeHandle& nh, slamData startupData); 00219 void assignPose(geometry_msgs::PoseStamped& pPose, Mat& C); 00220 00221 void estimatePose(vector<unsigned int>& basisNodes, unsigned int idx); 00222 00223 void getBasisNodes(vector<unsigned int>& basisNodes, unsigned int idx); 00224 00225 // Callbacks 00226 void handle_tracks(const thermalvis::feature_tracksConstPtr& msg); 00227 void handle_info(const sensor_msgs::CameraInfoConstPtr& info_msg); 00228 void main_loop(const ros::TimerEvent& event); 00229 00230 // Routines 00231 bool formInitialStructure(); 00232 bool findStartingFrames(); 00233 void refreshPoses(); 00234 bool checkForKeyframe(); 00235 void processNextFrame(); 00236 void update_display(); 00237 void show_poses(); 00238 void update_cameras_to_pnp(); 00239 double assignStartingFrames(unsigned int best_iii, unsigned int best_jjj, double* keyframe_scores, Mat& startingTrans); 00240 00241 void getGuidingPose(Mat *srcs, Mat& dst, unsigned int idx); 00242 00243 void clearSystem(); 00244 00245 void processScorecard(); 00246 00247 void serverCallback(thermalvis::monoslamConfig &config, uint32_t level); 00248 00249 // Misc 00250 bool stillTracking() { 00251 return isTracking; 00252 } 00253 00254 void prepareForTermination(); 00255 00256 }; 00257 00258 boost::shared_ptr < slamNode > *globalNodePtr; 00259 00260 #endif