libvisp_tracker/tracker.cpp
Go to the documentation of this file.
1 #include <stdexcept>
2 
3 #include <boost/filesystem/fstream.hpp>
4 #include <boost/format.hpp>
5 #include <boost/scope_exit.hpp>
6 #include <boost/version.hpp>
7 
8 #include <dynamic_reconfigure/server.h>
9 #include <geometry_msgs/PoseWithCovarianceStamped.h>
12 #include <ros/param.h>
13 #include <ros/ros.h>
14 #include <ros/transport_hints.h>
15 #include <sensor_msgs/Image.h>
16 #include <std_msgs/String.h>
18 
19 #include <boost/bind.hpp>
20 #include <visp3/core/vpExponentialMap.h>
21 #include <visp3/core/vpImage.h>
22 #include <visp3/core/vpImageConvert.h>
23 #include <visp3/core/vpCameraParameters.h>
24 
25 #include "tracker.hh"
26 
27 #include "conversion.hh"
28 #include "callbacks.hh"
29 #include "file.hh"
30 #include "names.hh"
31 
32 // TODO:
33 // - add a topic allowing to suggest an estimation of the cMo
34 // - handle automatic reset when tracking is lost.
35 
36 namespace visp_tracker
37 {
38  bool
39  Tracker::initCallback(visp_tracker::Init::Request& req,
40  visp_tracker::Init::Response& res)
41  {
42  ROS_INFO("Initialization request received.");
43 
44  res.initialization_succeed = false;
45 
46  // If something goes wrong, rollback all changes.
47  BOOST_SCOPE_EXIT((&res)(&tracker_)(&state_)
49  {
50  if(!res.initialization_succeed)
51  {
52  tracker_.resetTracker();
55 
56  }
57  } BOOST_SCOPE_EXIT_END;
58 
59  std::string fullModelPath;
60  boost::filesystem::ofstream modelStream;
61 
62  // Load model from parameter.
63  if (!makeModelFile(modelStream, fullModelPath))
64  return true;
65 
66  tracker_.resetTracker();
67 
68  // Common parameters
70 
71  if(trackerType_!="klt"){ // for mbt and hybrid
73  }
74 
75  if(trackerType_!="mbt"){ // for klt and hybrid
77  }
78 
79  if(trackerType_=="mbt+klt"){ // Hybrid Tracker reconfigure
80  visp_tracker::ModelBasedSettingsConfig config;
81  convertVpMbTrackerToModelBasedSettingsConfig<visp_tracker::ModelBasedSettingsConfig>(tracker_, config);
82  reconfigureSrv_->updateConfig(config);
83  convertVpMeToModelBasedSettingsConfig<visp_tracker::ModelBasedSettingsConfig>(movingEdge_, tracker_, config);
84  reconfigureSrv_->updateConfig(config);
85  convertVpKltOpencvToModelBasedSettingsConfig<visp_tracker::ModelBasedSettingsConfig>(kltTracker_, tracker_, config);
86  reconfigureSrv_->updateConfig(config);
87  }
88  else if(trackerType_=="mbt"){ // Edge Tracker reconfigure
89  visp_tracker::ModelBasedSettingsEdgeConfig config;
90  convertVpMbTrackerToModelBasedSettingsConfig<visp_tracker::ModelBasedSettingsEdgeConfig>(tracker_, config);
91  reconfigureEdgeSrv_->updateConfig(config);
92  convertVpMeToModelBasedSettingsConfig<visp_tracker::ModelBasedSettingsEdgeConfig>(movingEdge_, tracker_, config);
93  reconfigureEdgeSrv_->updateConfig(config);
94  }
95  else{ // KLT Tracker reconfigure
96  visp_tracker::ModelBasedSettingsKltConfig config;
97  convertVpMbTrackerToModelBasedSettingsConfig<visp_tracker::ModelBasedSettingsKltConfig>(tracker_, config);
98  reconfigureKltSrv_->updateConfig(config);
99  convertVpKltOpencvToModelBasedSettingsConfig<visp_tracker::ModelBasedSettingsKltConfig>(kltTracker_, tracker_, config);
100  reconfigureKltSrv_->updateConfig(config);
101  }
102 
104  lastTrackedImage_ = 0;
105 
106  // Load the model.
107  try
108  {
109  ROS_DEBUG_STREAM("Trying to load the model Tracker: " << fullModelPath);
110  tracker_.loadModel(fullModelPath.c_str());
111  modelStream.close();
112  }
113  catch(...)
114  {
115  ROS_ERROR_STREAM("Failed to load the model: " << fullModelPath);
116  return true;
117  }
118  ROS_DEBUG("Model has been successfully loaded.");
119 
120  // Load the initial cMo.
121  transformToVpHomogeneousMatrix(cMo_, req.initial_cMo);
122 
123  // Enable covariance matrix.
124  tracker_.setCovarianceComputation(true);
125 
126  // Try to initialize the tracker.
127  ROS_INFO_STREAM("Initializing tracker with cMo:\n" << cMo_);
128  try
129  {
130  // Bug between setPose() and initFromPose() not present here due to previous call to resetTracker()
131  tracker_.initFromPose(image_, cMo_);
132  ROS_INFO("Tracker successfully initialized.");
133 
134  //movingEdge.print();
136  // - Moving edges.
137  if(trackerType_!="klt")
139 
140  if(trackerType_!="mbt")
142  }
143  catch(const std::string& str)
144  {
145  ROS_ERROR_STREAM("Tracker initialization has failed: " << str);
146  }
147 
148  // Initialization is valid.
149  res.initialization_succeed = true;
150  state_ = TRACKING;
151  return true;
152  }
153 
154  void
155  Tracker::updateMovingEdgeSites(visp_tracker::MovingEdgeSitesPtr sites)
156  {
157  if (!sites)
158  return;
159 
160  std::list<vpMbtDistanceLine*> linesList;
161 
162  if(trackerType_!="klt") { // For mbt and hybrid
163  tracker_.getLline(linesList, 0);
164 
165  std::list<vpMbtDistanceLine*>::iterator linesIterator = linesList.begin();
166 
167  bool noVisibleLine = true;
168  for (; linesIterator != linesList.end(); ++linesIterator)
169  {
170  vpMbtDistanceLine* line = *linesIterator;
171 
172 #if VISP_VERSION_INT >= VP_VERSION_INT(3,0,0) // ViSP >= 3.0.0
173  if (line && line->isVisible() && ! line->meline.empty())
174 #else
175  if (line && line->isVisible() && line->meline)
176 #endif
177  {
178 #if VISP_VERSION_INT >= VP_VERSION_INT(3,0,0) // ViSP >= 3.0.0
179  for(unsigned int a = 0 ; a < line->meline.size() ; a++)
180  {
181  if(line->meline[a] != NULL) {
182  std::list<vpMeSite>::const_iterator sitesIterator = line->meline[a]->getMeList().begin();
183  if (line->meline[a]->getMeList().empty())
184  ROS_DEBUG_THROTTLE(10, "no moving edge for a line");
185  for (; sitesIterator != line->meline[a]->getMeList().end(); ++sitesIterator)
186  {
187 #elif VISP_VERSION_INT >= VP_VERSION_INT(2,10,0) // ViSP >= 2.10.0
188  std::list<vpMeSite>::const_iterator sitesIterator = line->meline->getMeList().begin();
189  if (line->meline->getMeList().empty())
190  ROS_DEBUG_THROTTLE(10, "no moving edge for a line");
191  for (; sitesIterator != line->meline->getMeList().end(); ++sitesIterator)
192  {
193 #else
194  std::list<vpMeSite>::const_iterator sitesIterator = line->meline->list.begin();
195  if (line->meline->list.empty())
196  ROS_DEBUG_THROTTLE(10, "no moving edge for a line");
197  for (; sitesIterator != line->meline->list.end(); ++sitesIterator)
198  {
199 #endif
200  visp_tracker::MovingEdgeSite movingEdgeSite;
201  movingEdgeSite.x = sitesIterator->ifloat;
202  movingEdgeSite.y = sitesIterator->jfloat;
203 #if VISP_VERSION_INT < VP_VERSION_INT(2,10,0) // ViSP < 2.10.0
204  movingEdgeSite.suppress = sitesIterator->suppress;
205 #endif
206  sites->moving_edge_sites.push_back (movingEdgeSite);
207  }
208  noVisibleLine = false;
209  }
210 #if VISP_VERSION_INT >= VP_VERSION_INT(3,0,0) // ViSP >= 3.0.0
211  }
212  }
213 #endif
214  }
215  if (noVisibleLine)
216  ROS_DEBUG_THROTTLE(10, "no distance lines");
217 }
218 }
219 
220 void
221 Tracker::updateKltPoints(visp_tracker::KltPointsPtr klt)
222 {
223  if (!klt)
224  return;
225 
226 #if VISP_VERSION_INT < VP_VERSION_INT(2,10,0) // ViSP < 2.10.0
227  vpMbHiddenFaces<vpMbtKltPolygon> *poly_lst;
228  std::map<int, vpImagePoint> *map_klt;
229 
230  if(trackerType_!="mbt") { // For klt and hybrid
231  poly_lst = &dynamic_cast<vpMbKltTracker*>(tracker_)->getFaces();
232 
233  for(unsigned int i = 0 ; i < poly_lst->size() ; i++)
234  {
235  if((*poly_lst)[i])
236  {
237  map_klt = &((*poly_lst)[i]->getCurrentPoints());
238 
239  if(map_klt->size() > 3)
240  {
241  for (std::map<int, vpImagePoint>::iterator it=map_klt->begin(); it!=map_klt->end(); ++it)
242  {
243  visp_tracker::KltPoint kltPoint;
244  kltPoint.id = it->first;
245  kltPoint.i = it->second.get_i();
246  kltPoint.j = it->second.get_j();
247  klt->klt_points_positions.push_back (kltPoint);
248  }
249  }
250  }
251  }
252  }
253 #else // ViSP >= 2.10.0
254  std::list<vpMbtDistanceKltPoints*> poly_lst;
255  std::map<int, vpImagePoint> *map_klt;
256 
257  if(trackerType_!="mbt") { // For klt and hybrid
258  poly_lst = tracker_.getFeaturesKlt();
259 
260  for(std::list<vpMbtDistanceKltPoints*>::const_iterator it=poly_lst.begin(); it!=poly_lst.end(); ++it){
261  map_klt = &((*it)->getCurrentPoints());
262 
263  if((*it)->polygon->isVisible()){
264  if(map_klt->size() > 3)
265  {
266  for (std::map<int, vpImagePoint>::iterator it=map_klt->begin(); it!=map_klt->end(); ++it)
267  {
268  visp_tracker::KltPoint kltPoint;
269  kltPoint.id = it->first;
270  kltPoint.i = it->second.get_i();
271  kltPoint.j = it->second.get_j();
272  klt->klt_points_positions.push_back (kltPoint);
273  }
274  }
275  }
276  }
277  }
278 #endif
279 }
280 
282 {
283  ros::V_string topics;
284  topics.push_back(rectifiedImageTopic_);
285  checkInputs_.start(topics, 60.0);
286 }
287 
289  ros::NodeHandle& privateNh,
290  volatile bool& exiting,
291  unsigned queueSize)
292  : exiting_ (exiting),
293  queueSize_(queueSize),
294  nodeHandle_(nh),
295  nodeHandlePrivate_(privateNh),
298  image_(),
299  cameraPrefix_(),
302  modelPath_(),
304  mutex_ (),
305  //reconfigureSrv_(mutex_, nodeHandlePrivate_),
306  reconfigureSrv_(NULL),
307  reconfigureKltSrv_(NULL),
308  reconfigureEdgeSrv_(NULL),
313  initService_(),
314  header_(),
315  info_(),
316  kltTracker_(),
317  movingEdge_(),
320  checkInputs_(nodeHandle_, ros::this_node::getName()),
321  cMo_ (),
322  listener_ (),
323  worldFrameId_ (),
324  compensateRobotMotion_ (false),
326  childFrameId_ (),
329 {
330  // Set cMo to identity.
331  cMo_.eye();
332 
333  // Parameters.
334  nodeHandlePrivate_.param<std::string>("camera_prefix", cameraPrefix_, "");
335  nodeHandlePrivate_.param<std::string>("tracker_type", trackerType_, "mbt");
336  if(trackerType_=="mbt")
337  tracker_.setTrackerType(vpMbGenericTracker::EDGE_TRACKER);
338  else if(trackerType_=="klt")
339  tracker_.setTrackerType(vpMbGenericTracker::KLT_TRACKER);
340  else
341  tracker_.setTrackerType(vpMbGenericTracker::EDGE_TRACKER | vpMbGenericTracker::KLT_TRACKER);
342 
343  if (cameraPrefix_.empty ())
344  {
345  ROS_FATAL
346  ("The camera_prefix parameter not set.\n"
347  "Please relaunch the tracker while setting this parameter, i.e.\n"
348  "$ rosrun visp_tracker tracker _camera_prefix:=/my/camera");
349  ros::shutdown ();
350  return;
351  }
352  // Create global /camera_prefix param to avoid to remap in the launch files the tracker_client and tracker_viewer nodes
353  nodeHandle_.setParam("camera_prefix", cameraPrefix_);
354 
355  nodeHandle_.param<std::string>("frame_id", childFrameId_, "object_position");
356 
357  // Robot motion compensation.
358  nodeHandle_.param<std::string>("world_frame_id", worldFrameId_, "/odom");
359  nodeHandle_.param<bool>
360  ("compensate_robot_motion", compensateRobotMotion_, false);
361 
362  // Compute topic and services names.
364  ros::names::resolve(cameraPrefix_ + "/image_rect");
365 
366  // Check for subscribed topics.
367  checkInputs();
368 
369  // Result publisher.
371  nodeHandle_.advertise<geometry_msgs::PoseWithCovarianceStamped>
373 
375  nodeHandle_.advertise<geometry_msgs::TransformStamped>
377 
378  // Moving edge sites_ publisher.
380  nodeHandle_.advertise<visp_tracker::MovingEdgeSites>
382 
383  // Klt_points_ publisher.
385  nodeHandle_.advertise<visp_tracker::KltPoints>
387 
388  // Camera subscriber.
391  (rectifiedImageTopic_, queueSize_,
393 
394  // Object position hint subscriber.
395  typedef boost::function<
396  void (const geometry_msgs::TransformStampedConstPtr&)>
397  objectPositionHintCallback_t;
398  objectPositionHintCallback_t callback =
399  boost::bind (&Tracker::objectPositionHintCallback, this, _1);
401  nodeHandle_.subscribe<geometry_msgs::TransformStamped>
402  ("object_position_hint", queueSize_, callback);
403 
404  // Dynamic reconfigure.
405  if(trackerType_=="mbt+klt"){ // Hybrid Tracker reconfigure
409  boost::ref(nodeHandle_), boost::ref(tracker_),
410  boost::ref(image_), boost::ref(movingEdge_), boost::ref(kltTracker_),
411  boost::ref(mutex_), _1, _2);
412  reconfigureSrv_->setCallback(f);
413  }
414  else if(trackerType_=="mbt"){ // Edge Tracker reconfigure
418  boost::ref(nodeHandle_), boost::ref(tracker_),
419  boost::ref(image_), boost::ref(movingEdge_),
420  boost::ref(mutex_), _1, _2);
421  reconfigureEdgeSrv_->setCallback(f);
422  }
423  else{ // KLT Tracker reconfigure
427  boost::ref(nodeHandle_), boost::ref(tracker_),
428  boost::ref(image_), boost::ref(kltTracker_),
429  boost::ref(mutex_), _1, _2);
430  reconfigureKltSrv_->setCallback(f);
431  }
432 
433  // Wait for the image to be initialized.
434  waitForImage();
435  if (this->exiting())
436  return;
437  if (!image_.getWidth() || !image_.getHeight())
438  throw std::runtime_error("failed to retrieve image");
439 
440  // Tracker initialization.
442 
443  // Double check camera parameters.
444  if (cameraParameters_.get_px () == 0.
445  || cameraParameters_.get_px () == 1.
446  || cameraParameters_.get_py () == 0.
447  || cameraParameters_.get_py () == 1.
448  || cameraParameters_.get_u0 () == 0.
449  || cameraParameters_.get_u0 () == 1.
450  || cameraParameters_.get_v0 () == 0.
451  || cameraParameters_.get_v0 () == 1.)
452  ROS_WARN ("Dubious camera parameters detected.\n"
453  "\n"
454  "It seems that the matrix P from your camera\n"
455  "calibration topics is wrong.\n"
456  "The tracker will continue anyway, but you\n"
457  "should double check your calibration data,\n"
458  "especially if the model re-projection fails.\n"
459  "\n"
460  "This warning is triggered is px, py, u0 or v0\n"
461  "is set to 0. or 1. (exactly).");
462 
463  tracker_.setCameraParameters(cameraParameters_);
464  tracker_.setDisplayFeatures(false);
465 
467 
468  // Service declaration.
470  boost::bind(&Tracker::initCallback, this, _1, _2);
471 
473  (visp_tracker::init_service, initCallback);
474 }
475 
477 {
478  if(reconfigureSrv_ != NULL)
479  delete reconfigureSrv_;
480 
481  if(reconfigureKltSrv_ != NULL)
482  delete reconfigureKltSrv_;
483 
484  if(reconfigureEdgeSrv_ != NULL)
485  delete reconfigureEdgeSrv_;
486 }
487 
489 {
490  ros::Rate loopRateTracking(100);
491  tf::Transform transform;
492  std_msgs::Header lastHeader;
493 
494  while (!exiting())
495  {
496  // When a camera sequence is played several times,
497  // the seq id will decrease, in this case we want to
498  // continue the tracking.
499  if (header_.seq < lastHeader.seq)
500  lastTrackedImage_ = 0;
501 
502  if (lastTrackedImage_ < header_.seq)
503  {
505 
506  // If we can estimate the camera displacement using tf,
507  // we update the cMo to compensate for robot motion.
509  try
510  {
511  tf::StampedTransform stampedTransform;
513  (header_.frame_id, // camera frame name
514  header_.stamp, // current image time
515  header_.frame_id, // camera frame name
516  lastHeader.stamp, // last processed image time
517  worldFrameId_, // frame attached to the environment
518  stampedTransform
519  );
520  vpHomogeneousMatrix newMold;
521  transformToVpHomogeneousMatrix (newMold, stampedTransform);
522  cMo_ = newMold * cMo_;
523 
524  mutex_.lock();
525  tracker_.setPose(image_, cMo_);
526  mutex_.unlock();
527  }
528  catch(tf::TransformException& e)
529  {
530  mutex_.unlock();
531  }
532 
533  // If we are lost but an estimation of the object position
534  // is provided, use it to try to reinitialize the system.
535  if (state_ == LOST)
536  {
537  // If the last received message is recent enough,
538  // use it otherwise do nothing.
539  if (ros::Time::now () - objectPositionHint_.header.stamp
540  < ros::Duration (1.))
542  (cMo_, objectPositionHint_.transform);
543 
544  mutex_.lock();
545  tracker_.setPose(image_, cMo_);
546  mutex_.unlock();
547  }
548 
549  // We try to track the image even if we are lost,
550  // in the case the tracker recovers...
551  if (state_ == TRACKING || state_ == LOST)
552  try
553  {
554  mutex_.lock();
555  // tracker_->setPose(image_, cMo_); // Removed as it is not necessary when the pose is not modified from outside.
556  tracker_.track(image_);
557  tracker_.getPose(cMo_);
558  mutex_.unlock();
559  }
560  catch(...)
561  {
562  mutex_.unlock();
563  ROS_WARN_THROTTLE(10, "tracking lost");
564  state_ = LOST;
565  }
566 
567  // Publish the tracking result.
568  if (state_ == TRACKING)
569  {
570  geometry_msgs::Transform transformMsg;
571  vpHomogeneousMatrixToTransform(transformMsg, cMo_);
572 
573  // Publish position.
575  {
576  geometry_msgs::TransformStampedPtr objectPosition
577  (new geometry_msgs::TransformStamped);
578  objectPosition->header = header_;
579  objectPosition->child_frame_id = childFrameId_;
580  objectPosition->transform = transformMsg;
581  transformationPublisher_.publish(objectPosition);
582  }
583 
584  // Publish result.
586  {
587  geometry_msgs::PoseWithCovarianceStampedPtr result
588  (new geometry_msgs::PoseWithCovarianceStamped);
589  result->header = header_;
590  result->pose.pose.position.x =
591  transformMsg.translation.x;
592  result->pose.pose.position.y =
593  transformMsg.translation.y;
594  result->pose.pose.position.z =
595  transformMsg.translation.z;
596 
597  result->pose.pose.orientation.x =
598  transformMsg.rotation.x;
599  result->pose.pose.orientation.y =
600  transformMsg.rotation.y;
601  result->pose.pose.orientation.z =
602  transformMsg.rotation.z;
603  result->pose.pose.orientation.w =
604  transformMsg.rotation.w;
605  const vpMatrix& covariance =
606  tracker_.getCovarianceMatrix();
607  for (unsigned i = 0; i < covariance.getRows(); ++i)
608  for (unsigned j = 0; j < covariance.getCols(); ++j)
609  {
610  unsigned idx = i * covariance.getCols() + j;
611  if (idx >= 36)
612  continue;
613  result->pose.covariance[idx] = covariance[i][j];
614  }
615  resultPublisher_.publish(result);
616  }
617 
618  // Publish moving edge sites.
620  {
621  visp_tracker::MovingEdgeSitesPtr sites
622  (new visp_tracker::MovingEdgeSites);
623  updateMovingEdgeSites(sites);
624  sites->header = header_;
626  }
627  // Publish KLT points.
629  {
630  visp_tracker::KltPointsPtr klt
631  (new visp_tracker::KltPoints);
632  updateKltPoints(klt);
633  klt->header = header_;
635  }
636 
637  // Publish to tf.
638  transform.setOrigin
639  (tf::Vector3(transformMsg.translation.x,
640  transformMsg.translation.y,
641  transformMsg.translation.z));
642  transform.setRotation
644  (transformMsg.rotation.x,
645  transformMsg.rotation.y,
646  transformMsg.rotation.z,
647  transformMsg.rotation.w));
650  (transform,
651  header_.stamp,
652  header_.frame_id,
653  childFrameId_));
654  }
655  }
656 
657  lastHeader = header_;
658  spinOnce();
659  loopRateTracking.sleep();
660 
661  }
662 }
663 
664 // Make sure that we have an image *and* associated calibration
665 // data.
666 void
668 {
669  ros::Rate loop_rate(10);
670  while (!exiting()
671  && (!image_.getWidth() || !image_.getHeight())
672  && (!info_ || info_->K[0] == 0.))
673  {
674  //ROS_INFO_THROTTLE(1, "waiting for a rectified image...");
675  spinOnce();
676  loop_rate.sleep();
677  }
678 }
679 
680 void
682 (const geometry_msgs::TransformStampedConstPtr& transform)
683 {
684  objectPositionHint_ = *transform;
685 }
686 
687 } // end of namespace visp_tracker.
std::string rectifiedImageTopic_
Definition: tracker.hh:105
void convertInitRequestToVpMe(const visp_tracker::Init::Request &req, vpMbGenericTracker &tracker, vpMe &moving_edge)
Definition: conversion.cpp:207
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
#define ROS_FATAL(...)
void transformToVpHomogeneousMatrix(vpHomogeneousMatrix &dst, const geometry_msgs::Transform &src)
Definition: conversion.cpp:138
#define ROS_WARN_THROTTLE(rate,...)
void publish(const boost::shared_ptr< M > &message) const
f
image_transport::CameraSubscriber::Callback bindImageCallback(vpImage< unsigned char > &image)
Definition: callbacks.cpp:41
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsEdgeConfig >::reconfigureSrv_t * reconfigureEdgeSrv_
Definition: tracker.hh:116
#define ROS_DEBUG_THROTTLE(rate,...)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
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)
std::string moving_edge_sites_topic
void updateKltPoints(visp_tracker::KltPointsPtr klt)
void objectPositionHintCallback(const geometry_msgs::TransformStampedConstPtr &)
std::string getName(void *handle)
image_proc::AdvertisementChecker checkInputs_
Helper used to check that subscribed topics exist.
Definition: tracker.hh:136
std_msgs::Header header_
Definition: tracker.hh:125
std::string cameraInfoTopic_
Definition: tracker.hh:106
std::string worldFrameId_
Definition: tracker.hh:141
ros::Publisher resultPublisher_
Definition: tracker.hh:118
void reconfigureEdgeCallbackAndInitViewer(ros::NodeHandle &nh, vpMbGenericTracker &tracker, vpImage< unsigned char > &I, vpMe &moving_edge, boost::recursive_mutex &mutex, visp_tracker::ModelBasedSettingsEdgeConfig &config, uint32_t level)
Definition: callbacks.cpp:186
vpMbGenericTracker tracker_
Definition: tracker.hh:131
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
ros::Publisher movingEdgeSitesPublisher_
Definition: tracker.hh:121
std::string init_service
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
std::string childFrameId_
Definition: tracker.hh:145
std::string convertVpKltOpencvToRosMessage(const vpMbGenericTracker &tracker, const vpKltOpencv &klt)
Definition: conversion.cpp:106
vpKltOpencv kltTracker_
Definition: tracker.hh:128
#define ROS_WARN(...)
void convertInitRequestToVpKltOpencv(const visp_tracker::Init::Request &req, vpMbGenericTracker &tracker, vpKltOpencv &klt)
Definition: conversion.cpp:240
Tracker(ros::NodeHandle &nh, ros::NodeHandle &privateNh, volatile bool &exiting, unsigned queueSize=5u)
boost::recursive_mutex mutex_
Definition: tracker.hh:112
image_transport::ImageTransport imageTransport_
Definition: tracker.hh:97
ros::Subscriber objectPositionHintSubscriber_
Definition: tracker.hh:147
std::string convertVpMeToRosMessage(const vpMbGenericTracker &tracker, const vpMe &moving_edge)
Definition: conversion.cpp:90
boost::filesystem::path modelPath_
Definition: tracker.hh:108
void callback(const sensor_msgs::ImageConstPtr &msg)
ros::NodeHandle & nodeHandle_
Definition: tracker.hh:95
bool initCallback(visp_tracker::Init::Request &req, visp_tracker::Init::Response &res)
std::vector< std::string > V_string
void reconfigureCallbackAndInitViewer(ros::NodeHandle &nh, 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:173
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsKltConfig >::reconfigureSrv_t * reconfigureKltSrv_
Definition: tracker.hh:115
void reconfigureKltCallbackAndInitViewer(ros::NodeHandle &nh, vpMbGenericTracker &tracker, vpImage< unsigned char > &I, vpKltOpencv &kltTracker, boost::recursive_mutex &mutex, visp_tracker::ModelBasedSettingsKltConfig &config, uint32_t level)
Definition: callbacks.cpp:198
unsigned queueSize_
Definition: tracker.hh:93
#define ROS_INFO(...)
geometry_msgs::TransformStamped objectPositionHint_
Definition: tracker.hh:148
bool param(const std::string &param_name, T &param_val, const T &default_val) const
std::string cameraPrefix_
Definition: tracker.hh:104
image_transport::CameraSubscriber cameraSubscriber_
Definition: tracker.hh:110
void sendTransform(const StampedTransform &transform)
tf::TransformListener listener_
Definition: tracker.hh:140
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
sensor_msgs::CameraInfoConstPtr info_
Definition: tracker.hh:126
#define ROS_DEBUG_STREAM(args)
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
bool sleep()
unsigned lastTrackedImage_
Definition: tracker.hh:133
uint32_t getNumSubscribers() const
void updateMovingEdgeSites(visp_tracker::MovingEdgeSitesPtr sites)
#define ROS_INFO_STREAM(args)
std::string convertVpMbTrackerToRosMessage(const vpMbGenericTracker &tracker)
Definition: conversion.cpp:81
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsConfig >::reconfigureSrv_t * reconfigureSrv_
Definition: tracker.hh:114
tf::TransformBroadcaster transformBroadcaster_
Definition: tracker.hh:144
void initializeVpCameraFromCameraInfo(vpCameraParameters &cam, sensor_msgs::CameraInfoConstPtr info)
Definition: conversion.cpp:256
std::string object_position_covariance_topic
static Time now()
boost::function< bool(visp_tracker::Init::Request &, visp_tracker::Init::Response &res)> initCallback_t
Definition: tracker.hh:44
ros::ServiceServer initService_
Definition: tracker.hh:124
dynamic_reconfigure::Server< ConfigType > reconfigureSrv_t
Definition: tracker.hh:48
ROSCPP_DECL void shutdown()
std::string object_position_topic
void convertInitRequestToVpMbTracker(const visp_tracker::Init::Request &req, vpMbGenericTracker &tracker)
Definition: conversion.cpp:186
vpCameraParameters cameraParameters_
Definition: tracker.hh:130
#define ROS_ERROR_STREAM(args)
volatile bool & exiting_
Definition: tracker.hh:91
void vpHomogeneousMatrixToTransform(geometry_msgs::Transform &dst, const vpHomogeneousMatrix &src)
Definition: conversion.cpp:122
std::string klt_points_topic
ros::NodeHandle & nodeHandlePrivate_
Definition: tracker.hh:96
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
std::string trackerType_
Definition: tracker.hh:100
ros::Publisher kltPointsPublisher_
Definition: tracker.hh:122
bool makeModelFile(boost::filesystem::ofstream &modelStream, std::string &fullModelPath)
Definition: file.cpp:62
vpHomogeneousMatrix cMo_
Definition: tracker.hh:138
#define ROS_DEBUG(...)
ros::Publisher transformationPublisher_
Definition: tracker.hh:119


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