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.
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::displayText
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 #if VISP_VERSION_INT > VP_VERSION_INT(3,6,0)
468  cMo.build(pose);
469 #else
470  cMo.buildFrom(pose);
471 #endif
472  return cMo;
473  }
474  catch (...)
475  {
476  // Failed to retrieve initial pose since model path starts with http://, package://, file:///
477  // We try to read from temporary file /tmp/$USER/
478  std::string username;
479  vpIoTools::getUserName(username);
480 
481  std::string filename;
482 #if defined(_WIN32)
483  filename ="C:/temp/" + username;
484 #else
485  filename ="/tmp/" + username;
486 #endif
487  filename += "/" + modelName_ + ".0.pos";
488  ROS_INFO_STREAM("Try to read init pose from: " << filename);
489  if (vpIoTools::checkFilename(filename)) {
490  ROS_INFO_STREAM("Retrieve initial pose from: " << filename);
491  std::ifstream in( filename.c_str() );
492  vpPoseVector pose;
493  pose.load(in);
494 #if VISP_VERSION_INT > VP_VERSION_INT(3,6,0)
495  cMo.build(pose);
496 #else
497  cMo.buildFrom(pose);
498 #endif
499  in.close();
500  }
501 
502  return cMo;
503  }
504  }
505 
506  void
507  TrackerClient::saveInitialPose(const vpHomogeneousMatrix& cMo)
508  {
509  boost::filesystem::path initialPose = getInitialPoseFileFromModelName(modelName_, modelPath_);
510  boost::filesystem::ofstream file(initialPose);
511  if (!file.good())
512  {
513  // Failed to save initial pose since model path starts with http://, package://, file:///
514  // We create a temporary file in /tmp/$USER/
515  std::string username;
516  vpIoTools::getUserName(username);
517 
518  // Create a log filename to save velocities...
519  std::string logdirname;
520 #if defined(_WIN32)
521  logdirname ="C:/temp/" + username;
522 #else
523  logdirname ="/tmp/" + username;
524 #endif
525  // Test if the output path exist. If no try to create it
526  if (vpIoTools::checkDirectory(logdirname) == false) {
527  try {
528  vpIoTools::makeDirectory(logdirname);
529  }
530  catch (...) {
531  ROS_WARN_STREAM("Unable to create the folder " << logdirname << " to save the initial pose");
532  return;
533  }
534  }
535  std::string filename = logdirname + "/" + modelName_ + ".0.pos";
536  ROS_INFO_STREAM("Save initial pose in: " << filename);
537  std::fstream finitpos ;
538  finitpos.open(filename.c_str(), std::ios::out) ;
539  vpPoseVector pose;
540 #if VISP_VERSION_INT > VP_VERSION_INT(3,6,0)
541  pose.build(cMo);
542 #else
543  pose.buildFrom(cMo);
544 #endif
545 
546  finitpos << pose;
547  finitpos.close();
548  }
549  else {
550  ROS_INFO_STREAM("Save initial pose in: " << initialPose);
551  vpPoseVector pose;
552 #if VISP_VERSION_INT > VP_VERSION_INT(3,6,0)
553  pose.build(cMo);
554 #else
555  pose.buildFrom(cMo);
556 #endif
557  file << pose;
558  }
559  }
560 
563  {
564  points_t points;
565 
566  std::string init =
568  std::string resource = fetchResource(init);
569  std::stringstream file;
570  file << resource;
571 
572  if (!file.good())
573  {
574  boost::format fmt("failed to load initialization points: %1");
575  fmt % init;
576  throw std::runtime_error(fmt.str());
577  }
578 
579  char c;
580  // skip lines starting with # as comment
581  file.get(c);
582  while (!file.fail() && (c == '#')) {
583  file.ignore(256, '\n');
584  file.get(c);
585  }
586  file.unget();
587 
588  unsigned int npoints;
589  file >> npoints;
590  file.ignore(256, '\n'); // skip the rest of the line
591  ROS_INFO_STREAM("Number of 3D points " << npoints << "\n");
592 
593  if (npoints > 100000) {
594  throw vpException(vpException::badValue,
595  "Exceed the max number of points.");
596  }
597 
598  vpPoint point;
599  double X = 0., Y = 0., Z = 0.;
600  for (unsigned int i=0 ; i < npoints ; i++){
601  // skip lines starting with # as comment
602  file.get(c);
603  while (!file.fail() && (c == '#')) {
604  file.ignore(256, '\n');
605  file.get(c);
606  }
607  file.unget();
608 
609  file >> X >> Y >> Z ;
610  file.ignore(256, '\n'); // skip the rest of the line
611 
612  point.setWorldCoordinates(X,Y,Z) ; // (X,Y,Z)
613  points.push_back(point);
614  }
615 
616  return points;
617  }
618 
619  bool
620  TrackerClient::validatePose(const vpHomogeneousMatrix &cMo){
621  ros::Rate loop_rate(200);
622  vpImagePoint ip;
623  vpMouseButton::vpMouseButtonType button = vpMouseButton::button1;
624  vpDisplay::display(image_);
625  tracker_.setDisplayFeatures(false);
626  tracker_.display(image_, cMo, cameraParameters_, vpColor::green);
627  vpDisplay::displayFrame(image_, cMo, cameraParameters_,frameSize_,vpColor::none,2);
628  vpDisplay::displayText(image_, 15, 10,
629  "Left click to validate, right click to modify initial pose",
630  vpColor::red);
631  vpDisplay::flush(image_);
632  tracker_.setDisplayFeatures(true);
633 
634  do
635  {
636  ros::spinOnce();
637  loop_rate.sleep();
638  if (!ros::ok())
639  return false;
640  }
641  while(ros::ok() && !vpDisplay::getClick(image_, ip, button, false));
642 
643  if(button == vpMouseButton::button1)
644  return true;
645 
646  return false;
647  }
648 
649  void
651  {
652  ros::Rate loop_rate(200);
653  vpHomogeneousMatrix cMo;
654  vpImagePoint point (10, 10);
655 
656  cMo = loadInitialPose();
657  tracker_.initFromPose(image_, cMo);
658 
659  // Show last cMo.
660  vpImagePoint ip;
661  vpMouseButton::vpMouseButtonType button = vpMouseButton::button1;
662 
663  if(validatePose(cMo))
664  {
665  return;
666  }
667  vpDisplayX *initHelpDisplay = NULL;
668 
669  std::string helpImagePath;
670  nodeHandlePrivate_.param<std::string>("help_image_path", helpImagePath, "");
671  if (helpImagePath.empty()){
672 
674 
675  try{
677  char* tmpname = strdup("/tmp/tmpXXXXXX");
678  if (mkdtemp(tmpname) == NULL) {
679  ROS_ERROR_STREAM("Failed to create the temporary directory: " << strerror(errno));
680  }
681  else {
682  boost::filesystem::path path(tmpname);
683  path /= ("help.ppm");
684  free(tmpname);
685 
686  helpImagePath = path.native();
687  ROS_INFO("Copy help image from %s to %s", getHelpImageFileFromModelName(modelName_, modelPath_).c_str(),
688  helpImagePath.c_str());
689 
690 
691  FILE* f = fopen(helpImagePath.c_str(), "w");
692  fwrite(resource.data.get(), resource.size, 1, f);
693  fclose(f);
694  }
695  }
696  catch(...){
697  }
698 
699  ROS_WARN_STREAM("Auto detection of help file: " << helpImagePath);
700  }
701 
702  if (!helpImagePath.empty()){
703  try {
704  // check if the file exists
705  if (! vpIoTools::checkFilename(helpImagePath)) {
706  ROS_WARN("Error tracker initialization help image file \"%s\" doesn't exist", helpImagePath.c_str());
707  }
708  else {
709  ROS_INFO_STREAM("Load help image: " << helpImagePath);
710  int winx = 0;
711  int winy = 0;
712 #if VISP_VERSION_INT >= VP_VERSION_INT(2,10,0)
713  winx = image_.display->getWindowXPosition();
714  winy = image_.display->getWindowYPosition();
715 #endif
716  initHelpDisplay = new vpDisplayX (winx+image_.getWidth()+20, winy, "Init help image");
717 
718  vpImage<vpRGBa> initHelpImage;
719  vpImageIo::read(initHelpImage, helpImagePath);
720  initHelpDisplay->init(initHelpImage);
721  vpDisplay::display(initHelpImage);
722  vpDisplay::flush(initHelpImage);
723  }
724  } catch(vpException &e) {
725  ROS_WARN("Error diplaying tracker initialization help image file \"%s\":\n%s", helpImagePath.c_str(), e.what());
726  }
727  }
728 
730  imagePoints_t imagePoints;
731 
732  bool done = false;
733  while(!done){
734  vpDisplay::display(image_);
735  vpDisplay::flush(image_);
736 
737  imagePoints.clear();
738  for(unsigned i = 0; i < points.size(); ++i)
739  {
740  do
741  {
742  ros::spinOnce();
743  loop_rate.sleep();
744  if (!ros::ok())
745  return;
746  }
747  while(ros::ok() && !vpDisplay::getClick(image_, ip, button, false));
748 
749  imagePoints.push_back(ip);
750  vpDisplay::displayCross(image_, imagePoints.back(), 5, vpColor::green);
751  vpDisplay::flush(image_);
752  }
753 
754  tracker_.initFromPoints(image_,imagePoints,points);
755  tracker_.getPose(cMo);
756  if(validatePose(cMo))
757  done = true;
758  }
759  tracker_.initFromPose(image_, cMo);
760  saveInitialPose(cMo);
761  if (initHelpDisplay != NULL)
762  delete initHelpDisplay;
763  }
764 
765  void
767  points_t& points,
768  imagePoints_t& imagePoints,
769  ros::Rate& rate,
770  vpPose& pose)
771  {
772  vpImagePoint ip;
773  double x = 0., y = 0.;
774  boost::format fmt("click on point %u/%u");
775  fmt % (i + 1) % points.size(); // list points from 1 to n.
776 
777  // Click on the point.
778  vpMouseButton::vpMouseButtonType button = vpMouseButton::button1;
779  do
780  {
781  vpDisplay::display(image_);
782  vpDisplay::displayText
783  (image_, 15, 10,
784  fmt.str().c_str(),
785  vpColor::red);
786 
787  for (unsigned j = 0; j < imagePoints.size(); ++j)
788  vpDisplay::displayCross(image_, imagePoints[j], 5, vpColor::green);
789 
790  vpDisplay::flush(image_);
791  ros::spinOnce();
792  rate.sleep();
793  if (exiting())
794  return;
795  }
796  while(!vpDisplay::getClick(image_, ip, button, false));
797 
798  imagePoints.push_back(ip);
799  vpPixelMeterConversion::convertPoint(cameraParameters_, ip, x, y);
800  points[i].set_x(x);
801  points[i].set_y(y);
802  pose.addPoint(points[i]);
803  }
804 
805  void
807  {
808  ros::Rate loop_rate(10);
809  while (!exiting()
810  && (!image_.getWidth() || !image_.getHeight()))
811  {
812  ROS_INFO_THROTTLE(1, "waiting for a rectified image...");
813  ros::spinOnce();
814  loop_rate.sleep();
815  }
816  }
817 
818  std::string
819  TrackerClient::fetchResource(const std::string& s)
820  {
823  std::string result;
824  result.resize(resource.size);
825  unsigned i = 0;
826  for (; i < resource.size; ++i)
827  result[i] = resource.data.get()[i];
828  return result;
829  }
830 
831  bool
832  TrackerClient::makeModelFile(boost::filesystem::ofstream& modelStream,
833  const std::string& resourcePath,
834  std::string& fullModelPath)
835  {
836  std::string modelExt_ = ".cao";
837  bool caoWorked = true;
839 
840  try{
841  resource = resourceRetriever_.get(resourcePath + modelExt_);
842  }
843  catch(...){
844  caoWorked = false;
845  }
846 
847  if(!caoWorked){
848  modelExt_ = ".wrl";
849 
850  try{
851  resource = resourceRetriever_.get(resourcePath + modelExt_);
852  }
853  catch(...){
854  ROS_ERROR_STREAM("No .cao nor .wrl file found in: " << resourcePath);
855  }
856  }
857 
858  modelPathAndExt_ = resourcePath + modelExt_;
859 
860  //ROS_WARN_STREAM("Model file Make Client: " << resourcePath << modelExt_);
861 
862  // Crash after when model not found
863  std::string result;
864  result.resize(resource.size);
865  unsigned i = 0;
866  for (; i < resource.size; ++i)
867  result[i] = resource.data.get()[i];
868  result[resource.size];
869 
870  char* tmpname = strdup("/tmp/tmpXXXXXX");
871  if (mkdtemp(tmpname) == NULL)
872  {
874  ("Failed to create the temporary directory: " << strerror(errno));
875  return false;
876  }
877  boost::filesystem::path path(tmpname);
878  path /= ("model" + modelExt_);
879  free(tmpname);
880 
881  fullModelPath = path.native();
882 
883 
884  //ROS_WARN_STREAM("Model file Make Client Full path tmp: " << fullModelPath );
885 
886  modelStream.open(path);
887  if (!modelStream.good())
888  {
890  ("Failed to create the temporary file: " << path);
891  return false;
892  }
893  modelStream << result;
894  modelStream.flush();
895  return true;
896  }
897 } // end of namespace visp_tracker.
visp_tracker::TrackerClient::validatePose
bool validatePose(const vpHomogeneousMatrix &cMo)
Definition: tracker-client.cpp:620
resource_retriever::MemoryResource::size
uint32_t size
visp_tracker::TrackerClient::queueSize_
unsigned queueSize_
Definition: tracker-client.hh:95
visp_tracker::TrackerClient::reconfigureSrvStruct
Definition: tracker-client.hh:47
names.hh
ros::NodeHandle::setParam
void setParam(const std::string &key, bool b) const
ros::ServiceClient::waitForExistence
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
ros::this_node::getNamespace
const ROSCPP_DECL std::string & getNamespace()
visp_tracker::TrackerClient::reconfigureSrv_
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsConfig >::reconfigureSrv_t * reconfigureSrv_
Definition: tracker-client.hh:120
visp_tracker::TrackerClient::rectifiedImageTopic_
std::string rectifiedImageTopic_
Definition: tracker-client.hh:109
advertisement_checker.h
visp_tracker::TrackerClient::bModelPath_
boost::filesystem::path bModelPath_
Definition: tracker-client.hh:114
visp_tracker::TrackerClient::points_t
std::vector< vpPoint > points_t
Definition: tracker-client.hh:43
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
visp_tracker::TrackerClient::loadInitialPose
vpHomogeneousMatrix loadInitialPose()
Definition: tracker-client.cpp:437
visp_tracker::TrackerClient::modelName_
std::string modelName_
Definition: tracker-client.hh:106
visp_tracker::TrackerClient::startFromSavedPose_
bool startFromSavedPose_
Definition: tracker-client.hh:132
visp_tracker::init_service
std::string init_service
visp_tracker::TrackerClient::cameraInfoTopic_
std::string cameraInfoTopic_
Definition: tracker-client.hh:110
ros::param::get
ROSCPP_DECL bool get(const std::string &key, bool &b)
image_transport::ImageTransport::subscribeCamera
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())
convertVpMeToRosMessage
std::string convertVpMeToRosMessage(const vpMbGenericTracker &tracker, const vpMe &moving_edge)
Definition: conversion.cpp:90
s
XmlRpcServer s
convertVpMbTrackerToInitRequest
void convertVpMbTrackerToInitRequest(const vpMbGenericTracker &tracker, visp_tracker::Init &srv)
Definition: conversion.cpp:183
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
visp_tracker::TrackerClient::fetchResource
std::string fetchResource(const std::string &)
Definition: tracker-client.cpp:819
bindImageCallback
image_transport::CameraSubscriber::Callback bindImageCallback(vpImage< unsigned char > &image)
Definition: callbacks.cpp:41
resource_retriever::MemoryResource
ros::NodeHandle::serviceClient
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
reconfigureEdgeCallback
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
ros::spinOnce
ROSCPP_DECL void spinOnce()
visp_tracker::TrackerClient::modelPath_
std::string modelPath_
Definition: tracker-client.hh:104
visp_tracker::TrackerClient::exiting
bool exiting()
Definition: tracker-client.hh:88
visp_tracker::TrackerClient::cameraPrefix_
std::string cameraPrefix_
Definition: tracker-client.hh:108
visp_tracker::TrackerClient::mutex_
boost::recursive_mutex mutex_
Definition: tracker-client.hh:119
visp_tracker::TrackerClient::frameSize_
double frameSize_
Definition: tracker-client.hh:112
visp_tracker::TrackerClient::loadInitializationPoints
points_t loadInitializationPoints()
Definition: tracker-client.cpp:562
visp_tracker::TrackerClient::cameraSubscriber_
image_transport::CameraSubscriber cameraSubscriber_
Definition: tracker-client.hh:117
visp_tracker::TrackerClient::sendcMo
void sendcMo(const vpHomogeneousMatrix &cMo)
Definition: tracker-client.cpp:324
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
image_proc::AdvertisementChecker::start
void start(const ros::V_string &topics, double duration)
visp_tracker::TrackerClient::nodeHandlePrivate_
ros::NodeHandle & nodeHandlePrivate_
Definition: tracker-client.hh:98
resource_retriever::MemoryResource::data
boost::shared_array< uint8_t > data
ok
ROSCPP_DECL bool ok()
vpHomogeneousMatrixToTransform
void vpHomogeneousMatrixToTransform(geometry_msgs::Transform &dst, const vpHomogeneousMatrix &src)
Definition: conversion.cpp:122
visp_tracker
Definition: names.cpp:3
ros::names::resolve
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
f
f
visp_tracker::TrackerClient::imagePoints_t
std::vector< vpImagePoint > imagePoints_t
Definition: tracker-client.hh:44
visp_tracker::TrackerClient::info_
sensor_msgs::CameraInfoConstPtr info_
Definition: tracker-client.hh:125
convertVpMbTrackerToRosMessage
std::string convertVpMbTrackerToRosMessage(const vpMbGenericTracker &tracker)
Definition: conversion.cpp:81
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
visp_tracker::TrackerClient::movingEdge_
vpMe movingEdge_
Definition: tracker-client.hh:127
visp_tracker::TrackerClient::loadModel
void loadModel()
Definition: tracker-client.cpp:380
visp_tracker::TrackerClient::TrackerClient
TrackerClient(ros::NodeHandle &nh, ros::NodeHandle &privateNh, volatile bool &exiting, unsigned queueSize=5u)
Definition: tracker-client.cpp:42
reconfigureCallback
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
visp_tracker::TrackerClient::modelPathAndExt_
std::string modelPathAndExt_
Definition: tracker-client.hh:105
visp_tracker::TrackerClient::header_
std_msgs::Header header_
Definition: tracker-client.hh:124
conversion.hh
visp_tracker::TrackerClient::saveInitialPose
void saveInitialPose(const vpHomogeneousMatrix &cMo)
Definition: tracker-client.cpp:507
visp_tracker::model_description_param
std::string model_description_param
visp_tracker::TrackerClient::spin
void spin()
Definition: tracker-client.cpp:214
file.hh
resource_retriever::Retriever::get
MemoryResource get(const std::string &url)
getHelpImageFileFromModelName
std::string getHelpImageFileFromModelName(const std::string &modelName, const std::string &defaultPath)
Definition: file.cpp:26
visp_tracker::TrackerClient::imageTransport_
image_transport::ImageTransport imageTransport_
Definition: tracker-client.hh:100
ros::ServiceClient
visp_tracker::TrackerClient::reconfigureEdgeSrv_
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsEdgeConfig >::reconfigureSrv_t * reconfigureEdgeSrv_
Definition: tracker-client.hh:122
d
d
ROS_WARN
#define ROS_WARN(...)
visp_tracker::TrackerClient::confirmInit_
bool confirmInit_
Definition: tracker-client.hh:133
visp_tracker::TrackerClient::reconfigureKltSrv_
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsKltConfig >::reconfigureSrv_t * reconfigureKltSrv_
Definition: tracker-client.hh:121
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
callbacks.hh
package.h
initializeVpCameraFromCameraInfo
void initializeVpCameraFromCameraInfo(vpCameraParameters &cam, sensor_msgs::CameraInfoConstPtr info)
Definition: conversion.cpp:260
ros::Rate::sleep
bool sleep()
visp_tracker::init_service_viewer
std::string init_service_viewer
image_transport.h
reconfigureKltCallback
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
visp_tracker::TrackerClient::initPoint
void initPoint(unsigned &i, points_t &points, imagePoints_t &imagePoints, ros::Rate &rate, vpPose &pose)
Definition: tracker-client.cpp:766
getInitFileFromModelName
std::string getInitFileFromModelName(const std::string &modelName, const std::string &defaultPath)
Definition: file.cpp:17
getInitialPoseFileFromModelName
std::string getInitialPoseFileFromModelName(const std::string &modelName, const std::string &defaultPath)
Definition: file.cpp:53
convertVpKltOpencvToInitRequest
void convertVpKltOpencvToInitRequest(const vpKltOpencv &klt, const vpMbGenericTracker &tracker, visp_tracker::Init &srv)
Definition: conversion.cpp:230
convertVpKltOpencvToRosMessage
std::string convertVpKltOpencvToRosMessage(const vpMbGenericTracker &tracker, const vpKltOpencv &klt)
Definition: conversion.cpp:106
visp_tracker::TrackerClient::makeModelFile
bool makeModelFile(boost::filesystem::ofstream &modelStream, const std::string &resourcePath, std::string &fullModelPath)
Definition: tracker-client.cpp:832
convertVpMeToInitRequest
void convertVpMeToInitRequest(const vpMe &moving_edge, const vpMbGenericTracker &tracker, visp_tracker::Init &srv)
Definition: conversion.cpp:197
visp_tracker::TrackerClient::resourceRetriever_
resource_retriever::Retriever resourceRetriever_
Definition: tracker-client.hh:138
visp_tracker::TrackerClient::kltTracker_
vpKltOpencv kltTracker_
Definition: tracker-client.hh:128
visp_tracker::TrackerClient::checkInputs_
image_proc::AdvertisementChecker checkInputs_
Helper used to check that subscribed topics exist.
Definition: tracker-client.hh:136
tracker-client.hh
visp_tracker::TrackerClient::checkInputs
void checkInputs()
Make sure the topics we subscribe already exist.
Definition: tracker-client.cpp:205
ROS_ERROR
#define ROS_ERROR(...)
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
visp_tracker::TrackerClient::init
void init()
Definition: tracker-client.cpp:650
ros::Rate
ros::V_string
std::vector< std::string > V_string
visp_tracker::TrackerClient::waitForImage
void waitForImage()
Definition: tracker-client.cpp:806
visp_tracker::TrackerClient::cameraParameters_
vpCameraParameters cameraParameters_
Definition: tracker-client.hh:129
visp_tracker::TrackerClient::reconfigureSrvStruct::reconfigureSrv_t
dynamic_reconfigure::Server< ConfigType > reconfigureSrv_t
Definition: tracker-client.hh:48
ROS_INFO
#define ROS_INFO(...)
visp_tracker::TrackerClient::image_
image_t image_
Definition: tracker-client.hh:102
visp_tracker::TrackerClient::bInitPath_
boost::filesystem::path bInitPath_
Definition: tracker-client.hh:115
visp_tracker::TrackerClient::~TrackerClient
~TrackerClient()
Definition: tracker-client.cpp:311
visp_tracker::TrackerClient::trackerType_
std::string trackerType_
Definition: tracker-client.hh:111
param.h
visp_tracker::TrackerClient::nodeHandle_
ros::NodeHandle & nodeHandle_
Definition: tracker-client.hh:97
getModelFileFromModelName
std::string getModelFileFromModelName(const std::string &modelName, const std::string &defaultPath)
Definition: file.cpp:35
visp_tracker::TrackerClient::tracker_
vpMbGenericTracker tracker_
Definition: tracker-client.hh:130
ros::NodeHandle
visp_tracker::default_model_path
std::string default_model_path
ROS_INFO_THROTTLE
#define ROS_INFO_THROTTLE(period,...)


visp_tracker
Author(s): Thomas Moulard
autogenerated on Sat Aug 24 2024 02:54:56