$search
00001 #include <cstdlib> 00002 #include <fstream> 00003 #include <sstream> 00004 #include <stdexcept> 00005 00006 #include <boost/filesystem.hpp> 00007 #include <boost/filesystem/fstream.hpp> 00008 #include <boost/format.hpp> 00009 #include <boost/optional.hpp> 00010 #include <boost/version.hpp> 00011 00012 #include <ros/ros.h> 00013 #include <ros/param.h> 00014 #include <dynamic_reconfigure/server.h> 00015 #include <geometry_msgs/PoseWithCovarianceStamped.h> 00016 #include <image_proc/advertisement_checker.h> 00017 #include <image_transport/image_transport.h> 00018 #include <visp_tracker/Init.h> 00019 #include <visp_tracker/MovingEdgeConfig.h> 00020 00021 #include <visp/vpMe.h> 00022 #include <visp/vpPixelMeterConversion.h> 00023 #include <visp/vpPose.h> 00024 00025 #define protected public 00026 #include <visp/vpMbEdgeTracker.h> 00027 #undef protected 00028 00029 #include <visp/vpDisplayX.h> 00030 00031 #include "conversion.hh" 00032 #include "callbacks.hh" 00033 #include "file.hh" 00034 #include "names.hh" 00035 00036 #include "tracker-client.hh" 00037 00038 00039 namespace visp_tracker 00040 { 00041 TrackerClient::TrackerClient(ros::NodeHandle& nh, 00042 ros::NodeHandle& privateNh, 00043 volatile bool& exiting, 00044 unsigned queueSize) 00045 : exiting_ (exiting), 00046 queueSize_(queueSize), 00047 nodeHandle_(nh), 00048 nodeHandlePrivate_(privateNh), 00049 imageTransport_(nodeHandle_), 00050 image_(), 00051 modelPath_(), 00052 modelName_(), 00053 cameraPrefix_(), 00054 rectifiedImageTopic_(), 00055 cameraInfoTopic_(), 00056 vrmlPath_(), 00057 initPath_(), 00058 cameraSubscriber_(), 00059 mutex_(), 00060 reconfigureSrv_(mutex_, nodeHandlePrivate_), 00061 movingEdge_(), 00062 cameraParameters_(), 00063 tracker_(), 00064 startFromSavedPose_(), 00065 checkInputs_(), 00066 resourceRetriever_() 00067 { 00068 tracker_.resetTracker(); 00069 00070 // Parameters. 00071 nodeHandlePrivate_.param<std::string>("model_path", modelPath_, 00072 visp_tracker::default_model_path); 00073 nodeHandlePrivate_.param<std::string>("model_name", modelName_, ""); 00074 00075 nodeHandlePrivate_.param<bool> 00076 ("start_from_saved_pose", startFromSavedPose_, false); 00077 00078 nodeHandlePrivate_.param<bool> 00079 ("confirm_init", confirmInit_, true); 00080 00081 if (modelName_.empty ()) 00082 throw std::runtime_error 00083 ("empty model\n" 00084 "Relaunch the client while setting the model_name parameter, i.e.\n" 00085 "$ rosrun visp_tracker client _model_name:=my-model" 00086 ); 00087 00088 // Compute topic and services names. 00089 00090 ros::Rate rate (1); 00091 while (cameraPrefix_.empty ()) 00092 { 00093 if (!nodeHandle_.getParam ("camera_prefix", cameraPrefix_)) 00094 { 00095 ROS_WARN 00096 ("the camera_prefix parameter does not exist.\n" 00097 "This may mean that:\n" 00098 "- the tracker is not launched,\n" 00099 "- the tracker and viewer are not running in the same namespace." 00100 ); 00101 } 00102 else if (cameraPrefix_.empty ()) 00103 { 00104 ROS_INFO 00105 ("tracker is not yet initialized, waiting...\n" 00106 "You may want to launch the client to initialize the tracker."); 00107 } 00108 if (this->exiting()) 00109 return; 00110 rate.sleep (); 00111 } 00112 00113 rectifiedImageTopic_ = 00114 ros::names::resolve(cameraPrefix_ + "/image_rect"); 00115 cameraInfoTopic_ = 00116 ros::names::resolve(cameraPrefix_ + "/camera_info"); 00117 00118 // Check for subscribed topics. 00119 checkInputs(); 00120 00121 // Set callback for dynamic reconfigure. 00122 reconfigureCallback_t f = 00123 boost::bind(&reconfigureCallback, boost::ref(tracker_), 00124 boost::ref(image_), boost::ref(movingEdge_), 00125 boost::ref(mutex_), _1, _2); 00126 reconfigureSrv_.setCallback(f); 00127 00128 // Camera subscriber. 00129 cameraSubscriber_ = imageTransport_.subscribeCamera 00130 (rectifiedImageTopic_, queueSize_, 00131 bindImageCallback(image_, header_, info_)); 00132 00133 // Model loading. 00134 vrmlPath_ = getModelFileFromModelName(modelName_, modelPath_); 00135 initPath_ = getInitFileFromModelName(modelName_, modelPath_); 00136 00137 ROS_INFO_STREAM("VRML file: " << vrmlPath_); 00138 ROS_INFO_STREAM("Init file: " << initPath_); 00139 00140 // Check that required files exist. 00141 // if (!boost::filesystem::is_regular_file(vrmlPath_)) 00142 // { 00143 // boost::format fmt("VRML model %1% is not a regular file"); 00144 // fmt % vrmlPath_; 00145 // throw std::runtime_error(fmt.str()); 00146 // } 00147 // if (!boost::filesystem::is_regular_file(initPath_)) 00148 // { 00149 // boost::format fmt("Initialization file %1% is not a regular file"); 00150 // fmt % initPath_; 00151 // throw std::runtime_error(fmt.str()); 00152 // } 00153 00154 // Load the 3d model. 00155 loadModel(); 00156 00157 // Wait for the image to be initialized. 00158 waitForImage(); 00159 if (this->exiting()) 00160 return; 00161 if (!image_.getWidth() || !image_.getHeight()) 00162 throw std::runtime_error("failed to retrieve image"); 00163 00164 // Tracker initialization. 00165 // - Camera 00166 initializeVpCameraFromCameraInfo(cameraParameters_, info_); 00167 tracker_.setCameraParameters(cameraParameters_); 00168 tracker_.setDisplayMovingEdges(true); 00169 00170 // - Moving edges. 00171 movingEdge_.initMask(); 00172 tracker_.setMovingEdge(movingEdge_); 00173 00174 // Display camera parameters and moving edges settings. 00175 ROS_INFO_STREAM(cameraParameters_); 00176 movingEdge_.print(); 00177 } 00178 00179 void 00180 TrackerClient::checkInputs() 00181 { 00182 ros::V_string topics; 00183 topics.push_back(rectifiedImageTopic_); 00184 topics.push_back(cameraInfoTopic_); 00185 checkInputs_.start(topics, 60.0); 00186 } 00187 00188 void 00189 TrackerClient::spin() 00190 { 00191 boost::format fmtWindowTitle ("ViSP MBT tracker initialization - [ns: %s]"); 00192 fmtWindowTitle % ros::this_node::getNamespace (); 00193 00194 vpDisplayX d(image_, image_.getWidth(), image_.getHeight(), 00195 fmtWindowTitle.str().c_str()); 00196 00197 ros::Rate loop_rate_tracking(200); 00198 bool ok = false; 00199 vpHomogeneousMatrix cMo; 00200 vpImagePoint point (10, 10); 00201 while (!ok && !exiting()) 00202 { 00203 try 00204 { 00205 // Initialize. 00206 vpDisplay::display(image_); 00207 vpDisplay::flush(image_); 00208 if (!startFromSavedPose_) 00209 init(); 00210 else 00211 { 00212 cMo = loadInitialPose(); 00213 startFromSavedPose_ = false; 00214 tracker_.initFromPose(image_, cMo); 00215 } 00216 tracker_.getPose(cMo); 00217 00218 ROS_INFO_STREAM("initial pose [tx,ty,tz,tux,tuy,tuz]:\n" 00219 << vpPoseVector(cMo)); 00220 00221 // Track once to make sure initialization is correct. 00222 if (confirmInit_) 00223 { 00224 vpImagePoint ip; 00225 vpMouseButton::vpMouseButtonType button = 00226 vpMouseButton::button1; 00227 do 00228 { 00229 vpDisplay::display(image_); 00230 tracker_.track(image_); 00231 tracker_.display(image_, cMo, cameraParameters_, 00232 vpColor::red, 2); 00233 vpDisplay::displayCharString 00234 (image_, point, "tracking, click to initialize tracker", 00235 vpColor::red); 00236 vpDisplay::flush(image_); 00237 tracker_.getPose(cMo); 00238 00239 ros::spinOnce(); 00240 loop_rate_tracking.sleep(); 00241 if (exiting()) 00242 return; 00243 } 00244 while(!vpDisplay::getClick(image_, ip, button, false)); 00245 ok = true; 00246 } 00247 else 00248 ok = true; 00249 } 00250 catch(const std::runtime_error& e) 00251 { 00252 ROS_ERROR_STREAM("failed to initialize: " 00253 << e.what() << ", retrying..."); 00254 } 00255 catch(const std::string& str) 00256 { 00257 ROS_ERROR_STREAM("failed to initialize: " 00258 << str << ", retrying..."); 00259 } 00260 catch(...) 00261 { 00262 ROS_ERROR("failed to initialize, retrying..."); 00263 } 00264 } 00265 00266 ROS_INFO_STREAM("Initialization done, sending initial cMo:\n" << cMo); 00267 try 00268 { 00269 sendcMo(cMo); 00270 } 00271 catch(std::exception& e) 00272 { 00273 ROS_ERROR_STREAM("failed to send cMo: " << e.what ()); 00274 } 00275 catch(...) 00276 { 00277 ROS_ERROR("unknown error happened while sending the cMo, retrying..."); 00278 } 00279 } 00280 00281 void 00282 TrackerClient::sendcMo(const vpHomogeneousMatrix& cMo) 00283 { 00284 ros::ServiceClient client = 00285 nodeHandle_.serviceClient<visp_tracker::Init>(visp_tracker::init_service); 00286 visp_tracker::Init srv; 00287 00288 // Load the model and send it to the parameter server. 00289 std::string modelDescription = fetchResource 00290 (getModelFileFromModelName (modelName_, modelPath_)); 00291 nodeHandle_.setParam (model_description_param, modelDescription); 00292 00293 vpHomogeneousMatrixToTransform(srv.request.initial_cMo, cMo); 00294 00295 convertVpMeToInitRequest(movingEdge_, tracker_, srv); 00296 00297 ros::Rate rate (1); 00298 while (!client.waitForExistence ()) 00299 { 00300 ROS_INFO 00301 ("Waiting for the initialization service to become available."); 00302 rate.sleep (); 00303 } 00304 00305 if (client.call(srv)) 00306 { 00307 if (srv.response.initialization_succeed) 00308 ROS_INFO("Tracker initialized with success."); 00309 else 00310 throw std::runtime_error("failed to initialize tracker."); 00311 } 00312 else 00313 throw std::runtime_error("failed to call service init"); 00314 } 00315 00316 void 00317 TrackerClient::loadModel() 00318 { 00319 try 00320 { 00321 ROS_DEBUG_STREAM("Trying to load the model " 00322 << vrmlPath_.external_file_string()); 00323 00324 std::string modelPath; 00325 boost::filesystem::ofstream modelStream; 00326 if (!makeModelFile(modelStream, 00327 vrmlPath_.external_file_string(), 00328 modelPath)) 00329 throw std::runtime_error ("failed to retrieve model"); 00330 00331 tracker_.loadModel(modelPath.c_str()); 00332 ROS_INFO("VRML model has been successfully loaded."); 00333 00334 ROS_DEBUG_STREAM("Nb hidden faces: " 00335 << tracker_.faces.getPolygon().size()); 00336 00337 std::list<vpMbtDistanceLine *> linesList; 00338 tracker_.getLline(linesList); 00339 ROS_DEBUG_STREAM("Nb line: " << linesList.size()); 00340 ROS_DEBUG_STREAM("nline: " << tracker_.nline); 00341 ROS_DEBUG_STREAM("Visible faces: " << tracker_.nbvisiblepolygone); 00342 } 00343 catch(...) 00344 { 00345 boost::format fmt 00346 ("Failed to load the model %1%\n" 00347 "Do you use resource_retriever syntax?\n" 00348 "I.e. replace /my/model/path by file:///my/model/path"); 00349 fmt % vrmlPath_; 00350 throw std::runtime_error(fmt.str()); 00351 } 00352 } 00353 00354 vpHomogeneousMatrix 00355 TrackerClient::loadInitialPose() 00356 { 00357 vpHomogeneousMatrix cMo; 00358 cMo.eye(); 00359 00360 std::string initialPose = 00361 getInitialPoseFileFromModelName (modelName_, modelPath_); 00362 std::string resource; 00363 try 00364 { 00365 resource = fetchResource (initialPose); 00366 } 00367 catch (...) 00368 { 00369 ROS_WARN_STREAM 00370 ("failed to retrieve initial pose: " << initialPose << "\n" 00371 << "using identity as initial pose"); 00372 return cMo; 00373 } 00374 std::stringstream file; 00375 file << resource; 00376 00377 if (!file.good()) 00378 { 00379 ROS_WARN_STREAM("failed to load initial pose: " << initialPose << "\n" 00380 << "using identity as initial pose"); 00381 return cMo; 00382 } 00383 00384 vpPoseVector pose; 00385 for (unsigned i = 0; i < 6; ++i) 00386 if (file.good()) 00387 file >> pose[i]; 00388 else 00389 { 00390 ROS_WARN("failed to parse initial pose file"); 00391 return cMo; 00392 } 00393 cMo.buildFrom(pose); 00394 return cMo; 00395 } 00396 00397 void 00398 TrackerClient::saveInitialPose(const vpHomogeneousMatrix& cMo) 00399 { 00400 boost::filesystem::path initialPose = 00401 getInitialPoseFileFromModelName(modelName_, modelPath_); 00402 boost::filesystem::ofstream file(initialPose); 00403 if (!file.good()) 00404 { 00405 ROS_WARN_STREAM 00406 ("failed to save initial pose: " << initialPose 00407 <<"\n" 00408 <<"Note: this is normal is you use a remote resource." 00409 <<"\n" 00410 <<"I.e. your model path starts with http://, package://, etc."); 00411 return; 00412 } 00413 vpPoseVector pose; 00414 pose.buildFrom(cMo); 00415 file << pose; 00416 } 00417 00418 TrackerClient::points_t 00419 TrackerClient::loadInitializationPoints() 00420 { 00421 points_t points; 00422 00423 std::string init = 00424 getInitFileFromModelName(modelName_, modelPath_); 00425 std::string resource = fetchResource(init); 00426 std::stringstream file; 00427 file << resource; 00428 00429 if (!file.good()) 00430 { 00431 boost::format fmt("failed to load initialization points: %1"); 00432 fmt % init; 00433 throw std::runtime_error(fmt.str()); 00434 } 00435 00436 unsigned npoints = 0; 00437 file >> npoints; 00438 if (!file.good()) 00439 throw std::runtime_error("failed to read initialization file"); 00440 00441 double X = 0., Y = 0., Z = 0.; 00442 vpPoint point; 00443 for (unsigned i = 0; i < npoints; ++i) 00444 { 00445 if (!file.good()) 00446 throw std::runtime_error("failed to read initialization file"); 00447 file >> X >> Y >> Z; 00448 point.setWorldCoordinates(X,Y,Z); 00449 points.push_back(point); 00450 } 00451 return points; 00452 } 00453 00454 bool 00455 TrackerClient::validatePose(const vpHomogeneousMatrix &cMo){ 00456 ros::Rate loop_rate(200); 00457 vpImagePoint ip; 00458 vpMouseButton::vpMouseButtonType button = vpMouseButton::button1; 00459 00460 vpDisplay::display(image_); 00461 tracker_.display(image_, cMo, cameraParameters_, vpColor::green); 00462 vpDisplay::displayFrame(image_, cMo, cameraParameters_,0.05, vpColor::green); 00463 vpDisplay::displayCharString(image_, 15, 10, 00464 "left click to validate, right click to modify initial pose", 00465 vpColor::red); 00466 vpDisplay::flush(image_); 00467 00468 do 00469 { 00470 ros::spinOnce(); 00471 loop_rate.sleep(); 00472 if (!ros::ok()) 00473 return false; 00474 } 00475 while(ros::ok() && !vpDisplay::getClick(image_, ip, button, false)); 00476 00477 if(button == vpMouseButton::button1) 00478 return true; 00479 00480 return false; 00481 } 00482 00483 void 00484 TrackerClient::init() 00485 { 00486 ros::Rate loop_rate(200); 00487 vpHomogeneousMatrix cMo; 00488 vpImagePoint point (10, 10); 00489 00490 cMo = loadInitialPose(); 00491 00492 // Show last cMo. 00493 vpImagePoint ip; 00494 vpMouseButton::vpMouseButtonType button = vpMouseButton::button1; 00495 00496 if(validatePose(cMo)) 00497 { 00498 tracker_.initFromPose(image_, cMo); 00499 return; 00500 } 00501 00502 points_t points = loadInitializationPoints(); 00503 imagePoints_t imagePoints; 00504 00505 bool done = false; 00506 while(!done){ 00507 vpDisplay::display(image_); 00508 vpDisplay::flush(image_); 00509 00510 imagePoints.clear(); 00511 for(unsigned i = 0; i < points.size(); ++i) 00512 { 00513 do 00514 { 00515 ros::spinOnce(); 00516 loop_rate.sleep(); 00517 if (!ros::ok()) 00518 return; 00519 } 00520 while(ros::ok() && !vpDisplay::getClick(image_, ip, button, false)); 00521 00522 imagePoints.push_back(ip); 00523 vpDisplay::displayCross(image_, imagePoints.back(), 5, vpColor::green); 00524 vpDisplay::flush(image_); 00525 } 00526 00527 tracker_.initFromPoints(image_,imagePoints,points); 00528 tracker_.getPose(cMo); 00529 if(validatePose(cMo)) 00530 done = true; 00531 } 00532 tracker_.initFromPose(image_, cMo); 00533 saveInitialPose(cMo); 00534 } 00535 00536 void 00537 TrackerClient::initPoint(unsigned& i, 00538 points_t& points, 00539 imagePoints_t& imagePoints, 00540 ros::Rate& rate, 00541 vpPose& pose) 00542 { 00543 vpImagePoint ip; 00544 double x = 0., y = 0.; 00545 boost::format fmt("click on point %u/%u"); 00546 fmt % (i + 1) % points.size(); // list points from 1 to n. 00547 00548 // Click on the point. 00549 vpMouseButton::vpMouseButtonType button = vpMouseButton::button1; 00550 do 00551 { 00552 vpDisplay::display(image_); 00553 vpDisplay::displayCharString 00554 (image_, 15, 10, 00555 fmt.str().c_str(), 00556 vpColor::red); 00557 00558 for (unsigned j = 0; j < imagePoints.size(); ++j) 00559 vpDisplay::displayCross(image_, imagePoints[j], 5, vpColor::green); 00560 00561 vpDisplay::flush(image_); 00562 ros::spinOnce(); 00563 rate.sleep(); 00564 if (exiting()) 00565 return; 00566 } 00567 while(!vpDisplay::getClick(image_, ip, button, false)); 00568 00569 imagePoints.push_back(ip); 00570 vpPixelMeterConversion::convertPoint(cameraParameters_, ip, x, y); 00571 points[i].set_x(x); 00572 points[i].set_y(y); 00573 pose.addPoint(points[i]); 00574 } 00575 00576 void 00577 TrackerClient::waitForImage() 00578 { 00579 ros::Rate loop_rate(10); 00580 while (!exiting() 00581 && (!image_.getWidth() || !image_.getHeight())) 00582 { 00583 ROS_INFO_THROTTLE(1, "waiting for a rectified image..."); 00584 ros::spinOnce(); 00585 loop_rate.sleep(); 00586 } 00587 } 00588 00589 std::string 00590 TrackerClient::fetchResource(const std::string& s) 00591 { 00592 resource_retriever::MemoryResource resource = 00593 resourceRetriever_.get(s); 00594 std::string result; 00595 result.resize(resource.size); 00596 unsigned i = 0; 00597 for (; i < resource.size; ++i) 00598 result[i] = resource.data.get()[i]; 00599 return result; 00600 } 00601 00602 bool 00603 TrackerClient::makeModelFile(boost::filesystem::ofstream& modelStream, 00604 const std::string& resourcePath, 00605 std::string& fullModelPath) 00606 { 00607 resource_retriever::MemoryResource resource = 00608 resourceRetriever_.get(resourcePath); 00609 std::string result; 00610 result.resize(resource.size); 00611 unsigned i = 0; 00612 for (; i < resource.size; ++i) 00613 result[i] = resource.data.get()[i]; 00614 result[resource.size]; 00615 00616 char* tmpname = strdup("/tmp/tmpXXXXXX"); 00617 if (mkdtemp(tmpname) == NULL) 00618 { 00619 ROS_ERROR_STREAM 00620 ("Failed to create the temporary directory: " << strerror(errno)); 00621 return false; 00622 } 00623 boost::filesystem::path path(tmpname); 00624 path /= "model.wrl"; 00625 free(tmpname); 00626 00627 fullModelPath = path.external_file_string(); 00628 00629 modelStream.open(path); 00630 if (!modelStream.good()) 00631 { 00632 ROS_ERROR_STREAM 00633 ("Failed to create the temporary file: " << path); 00634 return false; 00635 } 00636 modelStream << result; 00637 modelStream.flush(); 00638 return true; 00639 } 00640 } // end of namespace visp_tracker.