tracker-client.cpp
Go to the documentation of this file.
1 #include <cstdlib>
2 #include <fstream>
3 #include <sstream>
4 #include <stdexcept>
5 
6 #include <boost/filesystem.hpp>
7 #include <boost/filesystem/fstream.hpp>
8 #include <boost/format.hpp>
9 #include <boost/optional.hpp>
10 #include <boost/version.hpp>
11 
12 #include <ros/ros.h>
13 #include <ros/param.h>
14 #include <ros/package.h>
15 #include <dynamic_reconfigure/server.h>
16 #include <geometry_msgs/PoseWithCovarianceStamped.h>
19 #include <visp_tracker/Init.h>
20 #include <visp_tracker/ModelBasedSettingsConfig.h>
21 
22 #include <visp3/me/vpMe.h>
23 #include <visp3/core/vpPixelMeterConversion.h>
24 #include <visp3/vision/vpPose.h>
25 
26 #include <visp3/mbt/vpMbGenericTracker.h>
27 
28 #include <visp3/gui/vpDisplayX.h>
29 #include <visp3/io/vpImageIo.h>
30 #include <visp3/core/vpIoTools.h>
31 
32 #include "conversion.hh"
33 #include "callbacks.hh"
34 #include "file.hh"
35 #include "names.hh"
36 
37 #include "tracker-client.hh"
38 
39 
40 namespace visp_tracker
41 {
43  ros::NodeHandle& privateNh,
44  volatile bool& exiting,
45  unsigned queueSize)
46  : exiting_ (exiting),
47  queueSize_(queueSize),
48  nodeHandle_(nh),
49  nodeHandlePrivate_(privateNh),
50  imageTransport_(nodeHandle_),
51  image_(),
52  modelPath_(),
53  modelPathAndExt_(),
54  modelName_(),
55  cameraPrefix_(),
56  rectifiedImageTopic_(),
57  cameraInfoTopic_(),
58  trackerType_("mbt"),
59  frameSize_(0.1),
60  bModelPath_(),
61  bInitPath_(),
62  cameraSubscriber_(),
63  mutex_(),
64  reconfigureSrv_(NULL),
65  reconfigureKltSrv_(NULL),
66  reconfigureEdgeSrv_(NULL),
67  movingEdge_(),
68  kltTracker_(),
69  cameraParameters_(),
70  tracker_(),
71  startFromSavedPose_(),
72  checkInputs_(),
73  resourceRetriever_()
74  {
75  // Parameters.
76  nodeHandlePrivate_.param<std::string>("model_path", modelPath_,
78  nodeHandlePrivate_.param<std::string>("model_name", modelName_, "");
79 
81  ("start_from_saved_pose", startFromSavedPose_, false);
82 
84  ("confirm_init", confirmInit_, true);
85 
86  nodeHandlePrivate_.param<std::string>("tracker_type", trackerType_, "mbt");
87  if(trackerType_=="mbt")
88  tracker_.setTrackerType(vpMbGenericTracker::EDGE_TRACKER);
89  else if(trackerType_=="klt")
90  tracker_.setTrackerType(vpMbGenericTracker::KLT_TRACKER);
91  else
92  tracker_.setTrackerType(vpMbGenericTracker::EDGE_TRACKER | vpMbGenericTracker::KLT_TRACKER);
93 
94  nodeHandlePrivate_.param<double>("frame_size", frameSize_, 0.1);
95 
96  if (modelName_.empty ())
97  throw std::runtime_error
98  ("empty model\n"
99  "Relaunch the client while setting the model_name parameter, i.e.\n"
100  "$ rosrun visp_tracker client _model_name:=my-model"
101  );
102 
103  // Compute topic and services names.
104 
105  ros::Rate rate (1);
106  while (cameraPrefix_.empty ())
107  {
108  if (!nodeHandle_.getParam ("camera_prefix", cameraPrefix_) && !ros::param::get ("~camera_prefix", cameraPrefix_))
109  {
110  ROS_WARN
111  ("the camera_prefix parameter does not exist.\n"
112  "This may mean that:\n"
113  "- the tracker is not launched,\n"
114  "- the tracker and viewer are not running in the same namespace."
115  );
116  }
117  else if (cameraPrefix_.empty ())
118  {
119  ROS_INFO
120  ("tracker is not yet initialized, waiting...\n"
121  "You may want to launch the client to initialize the tracker.");
122  }
123  if (this->exiting())
124  return;
125  rate.sleep ();
126  }
127 
129  ros::names::resolve(cameraPrefix_ + "/image_rect");
131  ros::names::resolve(cameraPrefix_ + "/camera_info");
132 
133  // Check for subscribed topics.
134  checkInputs();
135 
136  // Camera subscriber.
140 
141  // Model loading.
142  bModelPath_ = getModelFileFromModelName(modelName_, modelPath_);
143  bInitPath_ = getInitFileFromModelName(modelName_, modelPath_);
144 
145  ROS_INFO_STREAM("Model file: " << bModelPath_);
146  ROS_INFO_STREAM("Init file: " << bInitPath_);
147 
148  // Load the 3d model.
149  loadModel();
150 
151  // Dynamic reconfigure.
152  if(trackerType_=="mbt+klt"){ // Hybrid Tracker reconfigure
155  boost::bind(&reconfigureCallback, boost::ref(tracker_),
156  boost::ref(image_), boost::ref(movingEdge_), boost::ref(kltTracker_),
157  boost::ref(mutex_), _1, _2);
158  reconfigureSrv_->setCallback(f);
159  }
160  else if(trackerType_=="mbt"){ // Edge Tracker reconfigure
163  boost::bind(&reconfigureEdgeCallback, boost::ref(tracker_),
164  boost::ref(image_), boost::ref(movingEdge_),
165  boost::ref(mutex_), _1, _2);
166  reconfigureEdgeSrv_->setCallback(f);
167  }
168  else{ // KLT Tracker reconfigure
171  boost::bind(&reconfigureKltCallback, boost::ref(tracker_),
172  boost::ref(image_), boost::ref(kltTracker_),
173  boost::ref(mutex_), _1, _2);
174  reconfigureKltSrv_->setCallback(f);
175  }
176 
177  // Wait for the image to be initialized.
178  waitForImage();
179  if (this->exiting())
180  return;
181  if (!image_.getWidth() || !image_.getHeight())
182  throw std::runtime_error("failed to retrieve image");
183 
184  // Tracker initialization.
185  // - Camera
187  tracker_.setCameraParameters(cameraParameters_);
188  tracker_.setDisplayFeatures(true);
189 
191  // - Moving edges.
192  if(trackerType_!="klt"){
194  }
195 
196  if(trackerType_!="mbt"){
198  }
199 
200  // Display camera parameters and moving edges settings.
202  }
203 
204  void
206  {
207  ros::V_string topics;
208  topics.push_back(rectifiedImageTopic_);
209  topics.push_back(cameraInfoTopic_);
210  checkInputs_.start(topics, 60.0);
211  }
212 
213  void
215  {
216  boost::format fmtWindowTitle ("ViSP MBT tracker initialization - [ns: %s]");
217  fmtWindowTitle % ros::this_node::getNamespace ();
218 
219  vpDisplayX d(image_, image_.getWidth(), image_.getHeight(),
220  fmtWindowTitle.str().c_str());
221 
222  ros::Rate loop_rate_tracking(200);
223  bool ok = false;
224  vpHomogeneousMatrix cMo;
225  vpImagePoint point (10, 10);
226  while (!ok && !exiting())
227  {
228  try
229  {
230  // Initialize.
231  vpDisplay::display(image_);
232  vpDisplay::flush(image_);
233  if (!startFromSavedPose_)
234  init();
235  else
236  {
237  cMo = loadInitialPose();
238  startFromSavedPose_ = false;
239  tracker_.initFromPose(image_, cMo);
240  }
241  tracker_.getPose(cMo);
242 
243  ROS_INFO_STREAM("initial pose [tx,ty,tz,tux,tuy,tuz]:\n" << vpPoseVector(cMo).t());
244 
245  // Track once to make sure initialization is correct.
246  if (confirmInit_)
247  {
248  vpImagePoint ip;
249  vpMouseButton::vpMouseButtonType button =
250  vpMouseButton::button1;
251  do
252  {
253  vpDisplay::display(image_);
254  mutex_.lock ();
255  tracker_.track(image_);
256  tracker_.getPose(cMo);
257  tracker_.display(image_, cMo, cameraParameters_,
258  vpColor::red, 2);
259  vpDisplay::displayFrame(image_, cMo, cameraParameters_,frameSize_,vpColor::none,2);
260  mutex_.unlock();
261  vpDisplay::displayCharString
262  (image_, point, "tracking, click to initialize tracker",
263  vpColor::red);
264  vpDisplay::flush(image_);
265 
266  ros::spinOnce();
267  loop_rate_tracking.sleep();
268  if (exiting())
269  return;
270  }
271  while(!vpDisplay::getClick(image_, ip, button, false));
272  ok = true;
273  }
274  else
275  ok = true;
276  }
277  catch(const std::runtime_error& e)
278  {
279  mutex_.unlock();
280  ROS_ERROR_STREAM("failed to initialize: "
281  << e.what() << ", retrying...");
282  }
283  catch(const std::string& str)
284  {
285  mutex_.unlock();
286  ROS_ERROR_STREAM("failed to initialize: "
287  << str << ", retrying...");
288  }
289  catch(...)
290  {
291  mutex_.unlock();
292  ROS_ERROR("failed to initialize, retrying...");
293  }
294  }
295 
296  ROS_INFO_STREAM("Initialization done, sending initial cMo:\n" << cMo);
297  try
298  {
299  sendcMo(cMo);
300  }
301  catch(std::exception& e)
302  {
303  ROS_ERROR_STREAM("failed to send cMo: " << e.what ());
304  }
305  catch(...)
306  {
307  ROS_ERROR("unknown error happened while sending the cMo, retrying...");
308  }
309  }
310 
312  {
313  if(reconfigureSrv_ != NULL)
314  delete reconfigureSrv_;
315 
316  if(reconfigureKltSrv_ != NULL)
317  delete reconfigureKltSrv_;
318 
319  if(reconfigureEdgeSrv_ != NULL)
320  delete reconfigureEdgeSrv_;
321  }
322 
323  void
324  TrackerClient::sendcMo(const vpHomogeneousMatrix& cMo)
325  {
326  ros::ServiceClient client =
328 
329 
330  ros::ServiceClient clientViewer =
332  visp_tracker::Init srv;
333 
334  // Load the model and send it to the parameter server.
335  std::string modelDescription = fetchResource(modelPathAndExt_);
336  nodeHandle_.setParam (model_description_param, modelDescription);
337 
338  vpHomogeneousMatrixToTransform(srv.request.initial_cMo, cMo);
339 
341 
342  if(trackerType_!="klt"){
344  }
345 
346  if(trackerType_!="mbt"){
348  }
349 
350  ros::Rate rate (1);
351  while (!client.waitForExistence ())
352  {
353  ROS_INFO
354  ("Waiting for the initialization service to become available.");
355  rate.sleep ();
356  }
357 
358  if (client.call(srv))
359  {
360  if (srv.response.initialization_succeed)
361  ROS_INFO("Tracker initialized with success.");
362  else
363  throw std::runtime_error("failed to initialize tracker.");
364  }
365  else
366  throw std::runtime_error("failed to call service init");
367 
368  if (clientViewer.call(srv))
369  {
370  if (srv.response.initialization_succeed)
371  ROS_INFO("Tracker Viewer initialized with success.");
372  else
373  throw std::runtime_error("failed to initialize tracker viewer.");
374  }
375  else
376  ROS_INFO("No Tracker Viewer node to initialize from service");
377  }
378 
379  void
381  {
382  try
383  {
384  ROS_DEBUG_STREAM("Trying to load the model "
385  << bModelPath_.native());
386 
387  std::string modelPath;
388  boost::filesystem::ofstream modelStream;
389  if (!makeModelFile(modelStream,
390  bModelPath_.native(),
391  modelPath))
392  throw std::runtime_error ("failed to retrieve model");
393 
394  tracker_.loadModel(modelPath);
395  ROS_INFO("Model has been successfully loaded.");
396 
397  if(trackerType_=="mbt"){
398  ROS_DEBUG_STREAM("Nb faces: "
399  << tracker_.getFaces().getPolygon().size());
400  ROS_DEBUG_STREAM("Nb visible faces: " << tracker_.getFaces().getNbVisiblePolygon());
401 
402  std::list<vpMbtDistanceLine *> linesList;
403  tracker_.getLline(linesList);
404  ROS_DEBUG_STREAM("Nb line: " << linesList.size());
405  //ROS_DEBUG_STREAM("nline: " << tracker_.nline);
406  }
407  else if(trackerType_=="klt"){
408  ROS_DEBUG_STREAM("Nb faces: "
409  << tracker_.getFaces().getPolygon().size());
410  ROS_DEBUG_STREAM("Nb visible faces: " << tracker_.getFaces().getNbVisiblePolygon());
411  ROS_DEBUG_STREAM("Nb KLT points: " << tracker_.getKltNbPoints());
412  }
413  else {
414  ROS_DEBUG_STREAM("Nb hidden faces: "
415  << tracker_.getFaces().getPolygon().size());
416  ROS_DEBUG_STREAM("Nb visible faces: " << tracker_.getFaces().getNbVisiblePolygon());
417  ROS_DEBUG_STREAM("Nb KLT points: " << tracker_.getKltNbPoints());
418 
419  std::list<vpMbtDistanceLine *> linesList;
420  tracker_.getLline(linesList);
421  ROS_DEBUG_STREAM("Nb line: " << linesList.size());
422  //ROS_DEBUG_STREAM("nline: " << tracker_.nline);
423  }
424  }
425  catch(...)
426  {
427  boost::format fmt
428  ("Failed to load the model %1%\n"
429  "Do you use resource_retriever syntax?\n"
430  "I.e. replace /my/model/path by file:///my/model/path");
431  fmt % bModelPath_;
432  throw std::runtime_error(fmt.str());
433  }
434  }
435 
436  vpHomogeneousMatrix
438  {
439  vpHomogeneousMatrix cMo;
440  cMo.eye();
441 
442  std::string initialPose = getInitialPoseFileFromModelName (modelName_, modelPath_);
443  std::string resource;
444  try
445  {
446  resource = fetchResource (initialPose);
447  std::stringstream file;
448  file << resource;
449 
450  if (!file.good())
451  {
452  ROS_WARN_STREAM("failed to load initial pose: " << initialPose << "\n"
453  << "using identity as initial pose");
454  return cMo;
455  }
456 
457  vpPoseVector pose;
458  for (unsigned i = 0; i < 6; ++i) {
459  if (file.good())
460  file >> pose[i];
461  else
462  {
463  ROS_WARN("failed to parse initial pose file");
464  return cMo;
465  }
466  }
467  cMo.buildFrom(pose);
468  return cMo;
469  }
470  catch (...)
471  {
472  // Failed to retrieve initial pose since model path starts with http://, package://, file:///
473  // We try to read from temporary file /tmp/$USER/
474  std::string username;
475  vpIoTools::getUserName(username);
476 
477  std::string filename;
478 #if defined(_WIN32)
479  filename ="C:/temp/" + username;
480 #else
481  filename ="/tmp/" + username;
482 #endif
483  filename += "/" + modelName_ + ".0.pos";
484  ROS_INFO_STREAM("Try to read init pose from: " << filename);
485  if (vpIoTools::checkFilename(filename)) {
486  ROS_INFO_STREAM("Retrieve initial pose from: " << filename);
487  std::ifstream in( filename.c_str() );
488  vpPoseVector pose;
489  pose.load(in);
490  cMo.buildFrom(pose);
491  in.close();
492  }
493 
494  return cMo;
495  }
496  }
497 
498  void
499  TrackerClient::saveInitialPose(const vpHomogeneousMatrix& cMo)
500  {
501  boost::filesystem::path initialPose = getInitialPoseFileFromModelName(modelName_, modelPath_);
502  boost::filesystem::ofstream file(initialPose);
503  if (!file.good())
504  {
505  // Failed to save initial pose since model path starts with http://, package://, file:///
506  // We create a temporary file in /tmp/$USER/
507  std::string username;
508  vpIoTools::getUserName(username);
509 
510  // Create a log filename to save velocities...
511  std::string logdirname;
512 #if defined(_WIN32)
513  logdirname ="C:/temp/" + username;
514 #else
515  logdirname ="/tmp/" + username;
516 #endif
517  // Test if the output path exist. If no try to create it
518  if (vpIoTools::checkDirectory(logdirname) == false) {
519  try {
520  vpIoTools::makeDirectory(logdirname);
521  }
522  catch (...) {
523  ROS_WARN_STREAM("Unable to create the folder " << logdirname << " to save the initial pose");
524  return;
525  }
526  }
527  std::string filename = logdirname + "/" + modelName_ + ".0.pos";
528  ROS_INFO_STREAM("Save initial pose in: " << filename);
529  std::fstream finitpos ;
530  finitpos.open(filename.c_str(), std::ios::out) ;
531  vpPoseVector pose;
532  pose.buildFrom(cMo);
533 
534  finitpos << pose;
535  finitpos.close();
536  }
537  else {
538  ROS_INFO_STREAM("Save initial pose in: " << initialPose);
539  vpPoseVector pose;
540  pose.buildFrom(cMo);
541  file << pose;
542  }
543  }
544 
547  {
548  points_t points;
549 
550  std::string init =
552  std::string resource = fetchResource(init);
553  std::stringstream file;
554  file << resource;
555 
556  if (!file.good())
557  {
558  boost::format fmt("failed to load initialization points: %1");
559  fmt % init;
560  throw std::runtime_error(fmt.str());
561  }
562 
563  char c;
564  // skip lines starting with # as comment
565  file.get(c);
566  while (!file.fail() && (c == '#')) {
567  file.ignore(256, '\n');
568  file.get(c);
569  }
570  file.unget();
571 
572  unsigned int npoints;
573  file >> npoints;
574  file.ignore(256, '\n'); // skip the rest of the line
575  ROS_INFO_STREAM("Number of 3D points " << npoints << "\n");
576 
577  if (npoints > 100000) {
578  throw vpException(vpException::badValue,
579  "Exceed the max number of points.");
580  }
581 
582  vpPoint point;
583  double X = 0., Y = 0., Z = 0.;
584  for (unsigned int i=0 ; i < npoints ; i++){
585  // skip lines starting with # as comment
586  file.get(c);
587  while (!file.fail() && (c == '#')) {
588  file.ignore(256, '\n');
589  file.get(c);
590  }
591  file.unget();
592 
593  file >> X >> Y >> Z ;
594  file.ignore(256, '\n'); // skip the rest of the line
595 
596  point.setWorldCoordinates(X,Y,Z) ; // (X,Y,Z)
597  points.push_back(point);
598  }
599 
600  return points;
601  }
602 
603  bool
604  TrackerClient::validatePose(const vpHomogeneousMatrix &cMo){
605  ros::Rate loop_rate(200);
606  vpImagePoint ip;
607  vpMouseButton::vpMouseButtonType button = vpMouseButton::button1;
608  vpDisplay::display(image_);
609  tracker_.setDisplayFeatures(false);
610  tracker_.display(image_, cMo, cameraParameters_, vpColor::green);
611  vpDisplay::displayFrame(image_, cMo, cameraParameters_,frameSize_,vpColor::none,2);
612  vpDisplay::displayCharString(image_, 15, 10,
613  "Left click to validate, right click to modify initial pose",
614  vpColor::red);
615  vpDisplay::flush(image_);
616  tracker_.setDisplayFeatures(true);
617 
618  do
619  {
620  ros::spinOnce();
621  loop_rate.sleep();
622  if (!ros::ok())
623  return false;
624  }
625  while(ros::ok() && !vpDisplay::getClick(image_, ip, button, false));
626 
627  if(button == vpMouseButton::button1)
628  return true;
629 
630  return false;
631  }
632 
633  void
635  {
636  ros::Rate loop_rate(200);
637  vpHomogeneousMatrix cMo;
638  vpImagePoint point (10, 10);
639 
640  cMo = loadInitialPose();
641  tracker_.initFromPose(image_, cMo);
642 
643  // Show last cMo.
644  vpImagePoint ip;
645  vpMouseButton::vpMouseButtonType button = vpMouseButton::button1;
646 
647  if(validatePose(cMo))
648  {
649  return;
650  }
651  vpDisplayX *initHelpDisplay = NULL;
652 
653  std::string helpImagePath;
654  nodeHandlePrivate_.param<std::string>("help_image_path", helpImagePath, "");
655  if (helpImagePath.empty()){
656 
658 
659  try{
661  char* tmpname = strdup("/tmp/tmpXXXXXX");
662  if (mkdtemp(tmpname) == NULL) {
663  ROS_ERROR_STREAM("Failed to create the temporary directory: " << strerror(errno));
664  }
665  else {
666  boost::filesystem::path path(tmpname);
667  path /= ("help.ppm");
668  free(tmpname);
669 
670  helpImagePath = path.native();
671  ROS_INFO("Copy help image from %s to %s", getHelpImageFileFromModelName(modelName_, modelPath_).c_str(),
672  helpImagePath.c_str());
673 
674 
675  FILE* f = fopen(helpImagePath.c_str(), "w");
676  fwrite(resource.data.get(), resource.size, 1, f);
677  fclose(f);
678  }
679  }
680  catch(...){
681  }
682 
683  ROS_WARN_STREAM("Auto detection of help file: " << helpImagePath);
684  }
685 
686  if (!helpImagePath.empty()){
687  try {
688  // check if the file exists
689  if (! vpIoTools::checkFilename(helpImagePath)) {
690  ROS_WARN("Error tracker initialization help image file \"%s\" doesn't exist", helpImagePath.c_str());
691  }
692  else {
693  ROS_INFO_STREAM("Load help image: " << helpImagePath);
694  int winx = 0;
695  int winy = 0;
696 #if VISP_VERSION_INT >= VP_VERSION_INT(2,10,0)
697  winx = image_.display->getWindowXPosition();
698  winy = image_.display->getWindowYPosition();
699 #endif
700  initHelpDisplay = new vpDisplayX (winx+image_.getWidth()+20, winy, "Init help image");
701 
702  vpImage<vpRGBa> initHelpImage;
703  vpImageIo::read(initHelpImage, helpImagePath);
704  initHelpDisplay->init(initHelpImage);
705  vpDisplay::display(initHelpImage);
706  vpDisplay::flush(initHelpImage);
707  }
708  } catch(vpException &e) {
709  ROS_WARN("Error diplaying tracker initialization help image file \"%s\":\n%s", helpImagePath.c_str(), e.what());
710  }
711  }
712 
714  imagePoints_t imagePoints;
715 
716  bool done = false;
717  while(!done){
718  vpDisplay::display(image_);
719  vpDisplay::flush(image_);
720 
721  imagePoints.clear();
722  for(unsigned i = 0; i < points.size(); ++i)
723  {
724  do
725  {
726  ros::spinOnce();
727  loop_rate.sleep();
728  if (!ros::ok())
729  return;
730  }
731  while(ros::ok() && !vpDisplay::getClick(image_, ip, button, false));
732 
733  imagePoints.push_back(ip);
734  vpDisplay::displayCross(image_, imagePoints.back(), 5, vpColor::green);
735  vpDisplay::flush(image_);
736  }
737 
738  tracker_.initFromPoints(image_,imagePoints,points);
739  tracker_.getPose(cMo);
740  if(validatePose(cMo))
741  done = true;
742  }
743  tracker_.initFromPose(image_, cMo);
744  saveInitialPose(cMo);
745  if (initHelpDisplay != NULL)
746  delete initHelpDisplay;
747  }
748 
749  void
751  points_t& points,
752  imagePoints_t& imagePoints,
753  ros::Rate& rate,
754  vpPose& pose)
755  {
756  vpImagePoint ip;
757  double x = 0., y = 0.;
758  boost::format fmt("click on point %u/%u");
759  fmt % (i + 1) % points.size(); // list points from 1 to n.
760 
761  // Click on the point.
762  vpMouseButton::vpMouseButtonType button = vpMouseButton::button1;
763  do
764  {
765  vpDisplay::display(image_);
766  vpDisplay::displayCharString
767  (image_, 15, 10,
768  fmt.str().c_str(),
769  vpColor::red);
770 
771  for (unsigned j = 0; j < imagePoints.size(); ++j)
772  vpDisplay::displayCross(image_, imagePoints[j], 5, vpColor::green);
773 
774  vpDisplay::flush(image_);
775  ros::spinOnce();
776  rate.sleep();
777  if (exiting())
778  return;
779  }
780  while(!vpDisplay::getClick(image_, ip, button, false));
781 
782  imagePoints.push_back(ip);
783  vpPixelMeterConversion::convertPoint(cameraParameters_, ip, x, y);
784  points[i].set_x(x);
785  points[i].set_y(y);
786  pose.addPoint(points[i]);
787  }
788 
789  void
791  {
792  ros::Rate loop_rate(10);
793  while (!exiting()
794  && (!image_.getWidth() || !image_.getHeight()))
795  {
796  ROS_INFO_THROTTLE(1, "waiting for a rectified image...");
797  ros::spinOnce();
798  loop_rate.sleep();
799  }
800  }
801 
802  std::string
803  TrackerClient::fetchResource(const std::string& s)
804  {
807  std::string result;
808  result.resize(resource.size);
809  unsigned i = 0;
810  for (; i < resource.size; ++i)
811  result[i] = resource.data.get()[i];
812  return result;
813  }
814 
815  bool
816  TrackerClient::makeModelFile(boost::filesystem::ofstream& modelStream,
817  const std::string& resourcePath,
818  std::string& fullModelPath)
819  {
820  std::string modelExt_ = ".wrl";
821  bool vrmlWorked = true;
823 
824  try{
825  resource = resourceRetriever_.get(resourcePath + modelExt_);
826  }
827  catch(...){
828  vrmlWorked = false;
829  }
830 
831  if(!vrmlWorked){
832  modelExt_ = ".cao";
833 
834  try{
835  resource = resourceRetriever_.get(resourcePath + modelExt_);
836  }
837  catch(...){
838  ROS_ERROR_STREAM("No .cao nor .wrl file found in: " << resourcePath);
839  }
840  }
841 
842  modelPathAndExt_ = resourcePath + modelExt_;
843 
844  //ROS_WARN_STREAM("Model file Make Client: " << resourcePath << modelExt_);
845 
846  // Crash after when model not found
847  std::string result;
848  result.resize(resource.size);
849  unsigned i = 0;
850  for (; i < resource.size; ++i)
851  result[i] = resource.data.get()[i];
852  result[resource.size];
853 
854  char* tmpname = strdup("/tmp/tmpXXXXXX");
855  if (mkdtemp(tmpname) == NULL)
856  {
858  ("Failed to create the temporary directory: " << strerror(errno));
859  return false;
860  }
861  boost::filesystem::path path(tmpname);
862  path /= ("model" + modelExt_);
863  free(tmpname);
864 
865  fullModelPath = path.native();
866 
867 
868  //ROS_WARN_STREAM("Model file Make Client Full path tmp: " << fullModelPath );
869 
870  modelStream.open(path);
871  if (!modelStream.good())
872  {
874  ("Failed to create the temporary file: " << path);
875  return false;
876  }
877  modelStream << result;
878  modelStream.flush();
879  return true;
880  }
881 } // end of namespace visp_tracker.
d
boost::filesystem::path bInitPath_
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
filename
TrackerClient(ros::NodeHandle &nh, ros::NodeHandle &privateNh, volatile bool &exiting, unsigned queueSize=5u)
f
image_transport::CameraSubscriber::Callback bindImageCallback(vpImage< unsigned char > &image)
Definition: callbacks.cpp:41
std::string getHelpImageFileFromModelName(const std::string &modelName, const std::string &defaultPath)
Definition: file.cpp:26
CameraSubscriber subscribeCamera(const std::string &base_topic, uint32_t queue_size, const CameraSubscriber::Callback &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
void start(const ros::V_string &topics, double duration)
void checkInputs()
Make sure the topics we subscribe already exist.
void saveInitialPose(const vpHomogeneousMatrix &cMo)
ros::NodeHandle & nodeHandle_
void convertVpMeToInitRequest(const vpMe &moving_edge, const vpMbGenericTracker &tracker, visp_tracker::Init &srv)
Definition: conversion.cpp:193
bool call(MReq &req, MRes &res)
image_transport::ImageTransport imageTransport_
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsEdgeConfig >::reconfigureSrv_t * reconfigureEdgeSrv_
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
ros::NodeHandle & nodeHandlePrivate_
std::string init_service
void convertVpMbTrackerToInitRequest(const vpMbGenericTracker &tracker, visp_tracker::Init &srv)
Definition: conversion.cpp:179
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::string convertVpKltOpencvToRosMessage(const vpMbGenericTracker &tracker, const vpKltOpencv &klt)
Definition: conversion.cpp:106
void convertVpKltOpencvToInitRequest(const vpKltOpencv &klt, const vpMbGenericTracker &tracker, visp_tracker::Init &srv)
Definition: conversion.cpp:226
std::vector< vpPoint > points_t
#define ROS_WARN(...)
resource_retriever::Retriever resourceRetriever_
bool validatePose(const vpHomogeneousMatrix &cMo)
vpHomogeneousMatrix loadInitialPose()
std::string getModelFileFromModelName(const std::string &modelName, const std::string &defaultPath)
Definition: file.cpp:35
image_proc::AdvertisementChecker checkInputs_
Helper used to check that subscribed topics exist.
std::string convertVpMeToRosMessage(const vpMbGenericTracker &tracker, const vpMe &moving_edge)
Definition: conversion.cpp:90
std::string getInitFileFromModelName(const std::string &modelName, const std::string &defaultPath)
Definition: file.cpp:17
void initPoint(unsigned &i, points_t &points, imagePoints_t &imagePoints, ros::Rate &rate, vpPose &pose)
std::vector< std::string > V_string
ROSCPP_DECL const std::string & getNamespace()
boost::shared_array< uint8_t > data
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
ROSCPP_DECL bool get(const std::string &key, std::string &s)
std::string getInitialPoseFileFromModelName(const std::string &modelName, const std::string &defaultPath)
Definition: file.cpp:53
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
std::string model_description_param
dynamic_reconfigure::Server< ConfigType > reconfigureSrv_t
ROSCPP_DECL bool ok()
image_transport::CameraSubscriber cameraSubscriber_
void reconfigureEdgeCallback(vpMbGenericTracker &tracker, vpImage< unsigned char > &I, vpMe &moving_edge, boost::recursive_mutex &mutex, visp_tracker::ModelBasedSettingsEdgeConfig &config, uint32_t level)
Definition: callbacks.cpp:92
TFSIMD_FORCE_INLINE const tfScalar & x() const
void sendcMo(const vpHomogeneousMatrix &cMo)
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
bool sleep()
MemoryResource get(const std::string &url)
vpMbGenericTracker tracker_
sensor_msgs::CameraInfoConstPtr info_
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsConfig >::reconfigureSrv_t * reconfigureSrv_
#define ROS_INFO_STREAM(args)
std::string convertVpMbTrackerToRosMessage(const vpMbGenericTracker &tracker)
Definition: conversion.cpp:81
void reconfigureCallback(vpMbGenericTracker &tracker, vpImage< unsigned char > &I, vpMe &moving_edge, vpKltOpencv &kltTracker, boost::recursive_mutex &mutex, visp_tracker::ModelBasedSettingsConfig &config, uint32_t level)
Definition: callbacks.cpp:56
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsKltConfig >::reconfigureSrv_t * reconfigureKltSrv_
bool getParam(const std::string &key, std::string &s) const
boost::filesystem::path bModelPath_
void initializeVpCameraFromCameraInfo(vpCameraParameters &cam, sensor_msgs::CameraInfoConstPtr info)
Definition: conversion.cpp:256
std::string default_model_path
#define ROS_INFO_THROTTLE(rate,...)
std::string init_service_viewer
#define ROS_ERROR_STREAM(args)
vpCameraParameters cameraParameters_
void vpHomogeneousMatrixToTransform(geometry_msgs::Transform &dst, const vpHomogeneousMatrix &src)
Definition: conversion.cpp:122
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
std::vector< vpImagePoint > imagePoints_t
void reconfigureKltCallback(vpMbGenericTracker &tracker, vpImage< unsigned char > &I, vpKltOpencv &kltTracker, boost::recursive_mutex &mutex, visp_tracker::ModelBasedSettingsKltConfig &config, uint32_t level)
Definition: callbacks.cpp:127
bool makeModelFile(boost::filesystem::ofstream &modelStream, const std::string &resourcePath, std::string &fullModelPath)
boost::recursive_mutex mutex_
std::string fetchResource(const std::string &)


visp_tracker
Author(s): Thomas Moulard
autogenerated on Sat Mar 13 2021 03:20:06