$search
00001 /* 00002 * Software License Agreement (Modified BSD License) 00003 * 00004 * Copyright (c) 2012, PAL Robotics, S.L. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of PAL Robotics, S.L. nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 * 00034 * @file learnsifts.cpp 00035 * @author Bence Magyar 00036 * @date April 2012 00037 * @version 0.2 00038 * @brief Main file of BLORT learnsifts node for ROS. Original source: Learnsifts.cpp of BLORT. 00039 */ 00040 #include <blort/Tracker/TextureTracker.h> 00041 #include <blort/Tracker/utilities.hpp> 00042 #include <blort/TomGine/tgModel.h> 00043 #include <blort/TomGine/tgModelLoader.h> 00044 #include <blort/TomGine/tgTimer.h> 00045 #include <blort/GLWindow/GLWindow.h> 00046 #include <blort/ThreadObject/RecognizerThread.h> 00047 00048 #include <ros/ros.h> 00049 #include <opencv2/core/core.hpp> 00050 #include <blort/blort/pal_util.h> 00051 00052 #include <blort_ros/TrackerConfidences.h> 00053 #include <image_transport/image_transport.h> 00054 #include <cv_bridge/cv_bridge.h> 00055 #include <sensor_msgs/image_encodings.h> 00056 #include <geometry_msgs/Pose.h> 00057 00058 cv::Mat lastImage; 00059 bool need_new_image = true; 00060 TomGine::tgCamera::Parameter tgCamParams; 00061 bool need_cam_init; 00062 ros::Subscriber cam_info_sub; 00063 sensor_msgs::CameraInfo camera_info; 00064 00065 void imageCb(const sensor_msgs::ImageConstPtr& msg) 00066 { 00067 cv_bridge::CvImagePtr cv_ptr; 00068 try 00069 { 00070 cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8); 00071 } 00072 catch (cv_bridge::Exception& e) 00073 { 00074 ROS_ERROR("cv_bridge exception: %s", e.what()); 00075 return; 00076 } 00077 00078 lastImage = cv_ptr->image; 00079 need_new_image = false; //FIXME remove 00080 } 00081 00082 void cam_info_callback(const sensor_msgs::CameraInfo &msg) 00083 { 00084 tgCamParams = TomGine::tgCamera::Parameter(msg); 00085 ROS_INFO("Camera parameters received."); 00086 camera_info = msg; 00087 need_cam_init = false; 00088 cam_info_sub.shutdown(); 00089 } 00090 00091 int main(int argc, char *argv[] ) 00092 { 00093 std::string config_root = argv[1]; 00094 00095 //this line should force opengl to run software rendering == no GPU 00096 //putenv("LIBGL_ALWAYS_INDIRECT=1"); 00097 00098 ros::init(argc, argv, "blort_learnsifts"); 00099 ros::NodeHandle nh("blort_learnsifts"); 00100 image_transport::ImageTransport it(nh); 00101 image_transport::Subscriber image_sub = it.subscribe("/blort_image", 1, &imageCb); 00102 cam_info_sub = nh.subscribe("/blort_camera", 1, &cam_info_callback); 00103 ros::Publisher confidences_pub = nh.advertise<blort_ros::TrackerConfidences>("confidences", 100); 00104 00105 printf("\n Learnsifts \n\n"); 00106 00107 printf(" Tracker control\n"); 00108 printf(" -------------------------------------------\n"); 00109 printf(" [q,Esc] Quit program\n"); 00110 printf(" [Return] Save SIFT and ply models.\n"); 00111 printf(" [Space] Save texture face and extract SIFTS.\n"); 00112 printf(" -------------------------------------------\n"); 00113 printf(" [4] Texture edge tracking\n"); 00114 printf(" [5] Texture color tracking\n"); 00115 printf(" [a] High accuracy tracking (less robust)\n"); 00116 printf(" [e] Show edges of image\n"); 00117 printf(" [i] Print tracking information to console\n"); 00118 printf(" [l] Lock/Unlock tracking\n"); 00119 printf(" [m] Switch display mode of model\n"); 00120 printf(" [p] Show particles\n"); 00121 printf(" [r] Reset tracker to initial pose\n"); 00122 printf(" [s] Save model to file (including textures)\n"); 00123 printf(" [t] Capture model texture from image\n"); 00124 printf(" [u] Untexture/remove texture from model\n"); 00125 printf(" \n\n "); 00126 00127 blortGLWindow::Event event; 00128 TomGine::tgTimer timer; 00129 std::vector<vec3> view_list; 00130 00131 // File names 00132 //FIXME: make these ROS parameters or eliminate them and use the content as parameters 00133 std::string pose_cal = pal_blort::addRoot("bin/pose.cal", config_root); 00134 std::string tracking_ini(pal_blort::addRoot("bin/tracking.ini", config_root)); 00135 std::string ply_model, sift_file, model_name; 00136 00137 GetPlySiftFilenames(tracking_ini.c_str(), ply_model, sift_file, model_name); 00138 printf("Object name: %s\n", model_name.c_str()); 00139 sift_file = pal_blort::addRoot(sift_file, config_root); 00140 00141 // Get Parameter from file 00142 TomGine::tgPose camPose, camPoseT; 00143 Tracking::Tracker::Parameter trackParams; 00144 GetTrackingParameter(trackParams, tracking_ini.c_str(), config_root); 00145 getCamPose(pose_cal.c_str(), camPose); 00146 camPoseT = camPose.Transpose(); 00147 00148 printf("=> Getting camera intrinsics ... "); 00149 // wait for the first camera_info message 00150 need_cam_init = true; 00151 while(need_cam_init) 00152 { 00153 ros::spinOnce(); 00154 } 00155 setCameraPose(tgCamParams, pose_cal.c_str()); 00156 trackParams.camPar = tgCamParams; 00157 00158 printf("OK\n"); 00159 00160 // Initialise image 00161 IplImage *image = cvCreateImage( cvSize(camera_info.width, camera_info.height), 8, 3 ); //FIXME dirty 00162 00163 printf("=> Initialising tracker ... "); 00164 00165 // Create OpenGL Window and Tracker 00166 CRecognizerThread* pThreadRec = 00167 new CRecognizerThread(blortRecognizer::CameraParameter(camera_info)); 00168 blortGLWindow::GLWindow window(trackParams.camPar.width, trackParams.camPar.height, "Training"); 00169 Tracking::TextureTracker tracker; 00170 tracker.init(trackParams); 00171 float rec_time = 0.0f; 00172 printf("OK\n"); 00173 00174 // Model for Tracker 00175 TomGine::tgPose trPose; 00176 trPose.t = vec3(0.0, 0.1, 0.0); 00177 trPose.Rotate(0.0f, 0.0f, 0.5f); 00178 std::string modelFullPath = pal_blort::addRoot(ply_model, config_root); 00179 printf("=> Trying to get the object model from file: %s\n", modelFullPath.c_str()); 00180 int modelID = tracker.addModelFromFile(modelFullPath.c_str(), trPose, model_name.c_str(), true); 00181 printf(" OK\n"); 00182 tracker.setLockFlag(true); 00183 00184 00185 00186 // Model for Recognizer / TomGine (ray-model intersection) 00187 TomGine::tgModel model; 00188 TomGine::tgPose tg_pose; 00189 TomGine::tgModelLoader modelloader; 00190 modelloader.LoadPly(model, pal_blort::addRoot(ply_model, config_root).c_str()); 00191 00192 Tracking::movement_state movement = Tracking::ST_FAST; 00193 Tracking::quality_state quality = Tracking::ST_OK; 00194 Tracking::confidence_state confidence = Tracking::ST_BAD; 00195 00196 need_new_image = true; 00197 while(need_new_image) 00198 { 00199 ros::spinOnce(); 00200 } 00201 *image = lastImage; 00202 00203 pThreadRec->Event(); 00204 00205 bool quit = false; 00206 while(!quit) 00207 { 00208 tracker.getModelMovementState(modelID, movement); 00209 tracker.getModelQualityState(modelID, quality); 00210 tracker.getModelConfidenceState(modelID, confidence); 00211 00212 if(confidence == Tracking::ST_GOOD && movement == Tracking::ST_STILL && quality != Tracking::ST_LOCKED) 00213 { 00214 ROS_WARN("Sorry, no learning with this node."); 00215 ROS_INFO("New initial pose fixed: \nt: [%f, %f, %f] \nq:[%f, %f, %f, %f]", 00216 trPose.t.x, 00217 trPose.t.y, 00218 trPose.t.z, 00219 trPose.q.x, 00220 trPose.q.y, 00221 trPose.q.z, 00222 trPose.q.w); 00223 } 00224 00225 //recovery, if object lost 00226 if(quality == Tracking::ST_LOST && rec_time > 0.2f) 00227 { 00228 // TomGine::tgPose recPose; 00229 // float conf; 00230 // 00231 // pThreadRec->Recognize(image, recPose, conf); 00232 // if(conf > recovery_conf_threshold) 00233 // { 00234 // ConvertCam2World(recPose, camPose, trPose); 00235 // tracker.setModelInitialPose(modelID, trPose); 00236 // tracker.resetUnlockLock(); 00237 // } 00238 // //tracker.reset(); 00239 // 00240 // ROS_INFO("orig conf: %f", conf); 00241 // 00242 // // if the recovery's confidence is high enough then 00243 // // kick the tracker out of this state and let it try 00244 // 00245 // 00246 // rec_time = 0.0f; 00247 // ROS_WARN("Tried to recover for the %d. time.", ++rec3dcounter); 00248 }else{ 00249 rec_time += timer.Update(); 00250 } 00251 00252 if(!need_new_image) 00253 { 00254 // Get image 00255 timer.Update(); 00256 *image = lastImage; 00257 00258 // Track object 00259 tracker.image_processing((unsigned char*)image->imageData); 00260 tracker.track(); 00261 00262 tracker.drawImage(0); 00263 tracker.drawCoordinates(); 00264 tracker.getModelPose(modelID, trPose); 00265 tracker.drawResult(2.0f); 00266 tg_pose = trPose; 00267 need_new_image = true; 00268 } 00269 // Keyboard inputs: 00270 while(window.GetEvent(event)){ 00271 quit = !InputControl(&tracker, event, config_root); 00272 if(event.type == blortGLWindow::TMGL_Press) 00273 { 00274 if(event.input == blortGLWindow::TMGL_Space) 00275 { 00276 // When hitting space bar -> Learn new sift features 00277 TomGine::tgPose pT1; 00278 TomGine::tgPose pT2, pT3, pT4; 00279 tracker.getModelPoseCamCoords(modelID, pT1); 00280 00281 mat3 R; vec3 a; 00282 pT1.GetPose(R, a); 00283 a = R.transpose() * pT1.t; 00284 a.normalize(); 00285 view_list.push_back(a); 00286 00287 pT2 = pT1; 00288 pThreadRec->LearnSifts(image, model, pT2); 00289 00290 std::vector<blortRecognizer::Siftex> sl; 00291 pThreadRec->GetLastSifts(sl); 00292 tracker.textureFromImage(true); 00293 } 00294 else if(event.input == blortGLWindow::TMGL_Return) 00295 { 00296 // When hitting Return -> Save sift model and recognize 00297 //TomGine::tgPose recPose; 00298 //float conf; 00299 pThreadRec->SaveSiftModel(sift_file.c_str()); 00300 //pThreadRec->Recognize(image, recPose, conf); 00301 //ConvertCam2World(recPose, camPose, trPose); 00302 //tracker.setModelInitialPose(modelID, trPose); 00303 //tracker.reset(modelID); 00304 tracker.saveModels(pal_blort::addRoot("Resources/ply/", config_root).c_str()); 00305 } 00306 } 00307 event.type = blortGLWindow::TMGL_None; 00308 } 00309 00310 window.Update(); 00311 00312 //publish tracker inner confidences just for fun 00313 Tracking::ModelEntry* myModelEntry = tracker.getModelEntry(modelID); 00314 blort_ros::TrackerConfidences tr_conf; 00315 tr_conf.edgeConf = myModelEntry->c_edge; 00316 tr_conf.confThreshold = myModelEntry->c_th; 00317 tr_conf.lostConf = myModelEntry->c_lost; 00318 tr_conf.distance = myModelEntry->t; 00319 confidences_pub.publish(tr_conf); 00320 00321 window.Activate(); 00322 ros::spinOnce(); 00323 } 00324 delete(pThreadRec); 00325 cvReleaseImage(&image); 00326 }