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 <visp/vpExponentialMap.h>
21 #include <visp/vpImage.h>
22 #include <visp/vpImageConvert.h>
23 #include <visp/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  dynamic_cast<vpMbEdgeTracker*>(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 = &dynamic_cast<vpMbKltTracker*>(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  //tracker_ = new vpMbEdgeTracker();
333 
334  // Parameters.
335  nodeHandlePrivate_.param<std::string>("camera_prefix", cameraPrefix_, "");
336  nodeHandlePrivate_.param<std::string>("tracker_type", trackerType_, "mbt");
337  if(trackerType_=="mbt")
338  tracker_ = new vpMbEdgeTracker();
339  else if(trackerType_=="klt")
340  tracker_ = new vpMbKltTracker();
341  else
342  tracker_ = new vpMbEdgeKltTracker();
343 
344  if (cameraPrefix_.empty ())
345  {
346  ROS_FATAL
347  ("The camera_prefix parameter not set.\n"
348  "Please relaunch the tracker while setting this parameter, i.e.\n"
349  "$ rosrun visp_tracker tracker _camera_prefix:=/my/camera");
350  ros::shutdown ();
351  return;
352  }
353  // Create global /camera_prefix param to avoid to remap in the launch files the tracker_client and tracker_viewer nodes
354  nodeHandle_.setParam("camera_prefix", cameraPrefix_);
355 
356  nodeHandle_.param<std::string>("frame_id", childFrameId_, "object_position");
357 
358  // Robot motion compensation.
359  nodeHandle_.param<std::string>("world_frame_id", worldFrameId_, "/odom");
360  nodeHandle_.param<bool>
361  ("compensate_robot_motion", compensateRobotMotion_, false);
362 
363  // Compute topic and services names.
365  ros::names::resolve(cameraPrefix_ + "/image_rect");
366 
367  // Check for subscribed topics.
368  checkInputs();
369 
370  // Result publisher.
372  nodeHandle_.advertise<geometry_msgs::PoseWithCovarianceStamped>
374 
376  nodeHandle_.advertise<geometry_msgs::TransformStamped>
378 
379  // Moving edge sites_ publisher.
381  nodeHandle_.advertise<visp_tracker::MovingEdgeSites>
383 
384  // Klt_points_ publisher.
386  nodeHandle_.advertise<visp_tracker::KltPoints>
388 
389  // Camera subscriber.
392  (rectifiedImageTopic_, queueSize_,
394 
395  // Object position hint subscriber.
396  typedef boost::function<
397  void (const geometry_msgs::TransformStampedConstPtr&)>
398  objectPositionHintCallback_t;
399  objectPositionHintCallback_t callback =
400  boost::bind (&Tracker::objectPositionHintCallback, this, _1);
402  nodeHandle_.subscribe<geometry_msgs::TransformStamped>
403  ("object_position_hint", queueSize_, callback);
404 
405  // Initialization.
406  // No more necessary as it is done via the reconfigure server
407 // movingEdge_.initMask();
408 // if(trackerType_!="klt"){
409 // vpMbEdgeTracker* t = dynamic_cast<vpMbEdgeTracker*>(tracker_);
410 // t->setMovingEdge(movingEdge_);
411 // }
412 
413 // if(trackerType_!="mbt"){
414 // vpMbKltTracker* t = dynamic_cast<vpMbKltTracker*>(tracker_);
415 // t->setKltOpencv(kltTracker_);
416 // }
417 
418  // Dynamic reconfigure.
419  if(trackerType_=="mbt+klt"){ // Hybrid Tracker reconfigure
423  boost::ref(nodeHandle_), boost::ref(tracker_),
424  boost::ref(image_), boost::ref(movingEdge_), boost::ref(kltTracker_),
425  boost::ref(mutex_), _1, _2);
426  reconfigureSrv_->setCallback(f);
427  }
428  else if(trackerType_=="mbt"){ // Edge Tracker reconfigure
432  boost::ref(nodeHandle_), boost::ref(tracker_),
433  boost::ref(image_), boost::ref(movingEdge_),
434  boost::ref(mutex_), _1, _2);
435  reconfigureEdgeSrv_->setCallback(f);
436  }
437  else{ // KLT Tracker reconfigure
441  boost::ref(nodeHandle_), boost::ref(tracker_),
442  boost::ref(image_), boost::ref(kltTracker_),
443  boost::ref(mutex_), _1, _2);
444  reconfigureKltSrv_->setCallback(f);
445  }
446 
447  // Wait for the image to be initialized.
448  waitForImage();
449  if (this->exiting())
450  return;
451  if (!image_.getWidth() || !image_.getHeight())
452  throw std::runtime_error("failed to retrieve image");
453 
454  // Tracker initialization.
456 
457  // Double check camera parameters.
458  if (cameraParameters_.get_px () == 0.
459  || cameraParameters_.get_px () == 1.
460  || cameraParameters_.get_py () == 0.
461  || cameraParameters_.get_py () == 1.
462  || cameraParameters_.get_u0 () == 0.
463  || cameraParameters_.get_u0 () == 1.
464  || cameraParameters_.get_v0 () == 0.
465  || cameraParameters_.get_v0 () == 1.)
466  ROS_WARN ("Dubious camera parameters detected.\n"
467  "\n"
468  "It seems that the matrix P from your camera\n"
469  "calibration topics is wrong.\n"
470  "The tracker will continue anyway, but you\n"
471  "should double check your calibration data,\n"
472  "especially if the model re-projection fails.\n"
473  "\n"
474  "This warning is triggered is px, py, u0 or v0\n"
475  "is set to 0. or 1. (exactly).");
476 
477  tracker_->setCameraParameters(cameraParameters_);
478  tracker_->setDisplayFeatures(false);
479 
481 
482  // Service declaration.
484  boost::bind(&Tracker::initCallback, this, _1, _2);
485 
487  (visp_tracker::init_service, initCallback);
488  }
489 
491  {
492  delete tracker_;
493 
494  if(reconfigureSrv_ != NULL)
495  delete reconfigureSrv_;
496 
497  if(reconfigureKltSrv_ != NULL)
498  delete reconfigureKltSrv_;
499 
500  if(reconfigureEdgeSrv_ != NULL)
501  delete reconfigureEdgeSrv_;
502  }
503 
505  {
506  ros::Rate loopRateTracking(100);
507  tf::Transform transform;
508  std_msgs::Header lastHeader;
509 
510  while (!exiting())
511  {
512  // When a camera sequence is played several times,
513  // the seq id will decrease, in this case we want to
514  // continue the tracking.
515  if (header_.seq < lastHeader.seq)
516  lastTrackedImage_ = 0;
517 
518  if (lastTrackedImage_ < header_.seq)
519  {
521 
522  // If we can estimate the camera displacement using tf,
523  // we update the cMo to compensate for robot motion.
525  try
526  {
527  tf::StampedTransform stampedTransform;
529  (header_.frame_id, // camera frame name
530  header_.stamp, // current image time
531  header_.frame_id, // camera frame name
532  lastHeader.stamp, // last processed image time
533  worldFrameId_, // frame attached to the environment
534  stampedTransform
535  );
536  vpHomogeneousMatrix newMold;
537  transformToVpHomogeneousMatrix (newMold, stampedTransform);
538  cMo_ = newMold * cMo_;
539 
540  mutex_.lock();
541  tracker_->setPose(image_, cMo_);
542  mutex_.unlock();
543  }
544  catch(tf::TransformException& e)
545  {
546  mutex_.unlock();
547  }
548 
549  // If we are lost but an estimation of the object position
550  // is provided, use it to try to reinitialize the system.
551  if (state_ == LOST)
552  {
553  // If the last received message is recent enough,
554  // use it otherwise do nothing.
555  if (ros::Time::now () - objectPositionHint_.header.stamp
556  < ros::Duration (1.))
558  (cMo_, objectPositionHint_.transform);
559 
560  mutex_.lock();
561  tracker_->setPose(image_, cMo_);
562  mutex_.unlock();
563  }
564 
565  // We try to track the image even if we are lost,
566  // in the case the tracker recovers...
567  if (state_ == TRACKING || state_ == LOST)
568  try
569  {
570  mutex_.lock();
571  // tracker_->setPose(image_, cMo_); // Removed as it is not necessary when the pose is not modified from outside.
572  tracker_->track(image_);
573  tracker_->getPose(cMo_);
574  mutex_.unlock();
575  }
576  catch(...)
577  {
578  mutex_.unlock();
579  ROS_WARN_THROTTLE(10, "tracking lost");
580  state_ = LOST;
581  }
582 
583  // Publish the tracking result.
584  if (state_ == TRACKING)
585  {
586  geometry_msgs::Transform transformMsg;
587  vpHomogeneousMatrixToTransform(transformMsg, cMo_);
588 
589  // Publish position.
591  {
592  geometry_msgs::TransformStampedPtr objectPosition
593  (new geometry_msgs::TransformStamped);
594  objectPosition->header = header_;
595  objectPosition->child_frame_id = childFrameId_;
596  objectPosition->transform = transformMsg;
597  transformationPublisher_.publish(objectPosition);
598  }
599 
600  // Publish result.
602  {
603  geometry_msgs::PoseWithCovarianceStampedPtr result
604  (new geometry_msgs::PoseWithCovarianceStamped);
605  result->header = header_;
606  result->pose.pose.position.x =
607  transformMsg.translation.x;
608  result->pose.pose.position.y =
609  transformMsg.translation.y;
610  result->pose.pose.position.z =
611  transformMsg.translation.z;
612 
613  result->pose.pose.orientation.x =
614  transformMsg.rotation.x;
615  result->pose.pose.orientation.y =
616  transformMsg.rotation.y;
617  result->pose.pose.orientation.z =
618  transformMsg.rotation.z;
619  result->pose.pose.orientation.w =
620  transformMsg.rotation.w;
621  const vpMatrix& covariance =
622  tracker_->getCovarianceMatrix();
623  for (unsigned i = 0; i < covariance.getRows(); ++i)
624  for (unsigned j = 0; j < covariance.getCols(); ++j)
625  {
626  unsigned idx = i * covariance.getCols() + j;
627  if (idx >= 36)
628  continue;
629  result->pose.covariance[idx] = covariance[i][j];
630  }
631  resultPublisher_.publish(result);
632  }
633 
634  // Publish moving edge sites.
636  {
637  visp_tracker::MovingEdgeSitesPtr sites
638  (new visp_tracker::MovingEdgeSites);
639  updateMovingEdgeSites(sites);
640  sites->header = header_;
642  }
643  // Publish KLT points.
645  {
646  visp_tracker::KltPointsPtr klt
647  (new visp_tracker::KltPoints);
648  updateKltPoints(klt);
649  klt->header = header_;
651  }
652 
653  // Publish to tf.
654  transform.setOrigin
655  (tf::Vector3(transformMsg.translation.x,
656  transformMsg.translation.y,
657  transformMsg.translation.z));
658  transform.setRotation
660  (transformMsg.rotation.x,
661  transformMsg.rotation.y,
662  transformMsg.rotation.z,
663  transformMsg.rotation.w));
666  (transform,
667  header_.stamp,
668  header_.frame_id,
669  childFrameId_));
670  }
671  }
672 
673  lastHeader = header_;
674  spinOnce();
675  loopRateTracking.sleep();
676 
677  }
678  }
679 
680  // Make sure that we have an image *and* associated calibration
681  // data.
682  void
684  {
685  ros::Rate loop_rate(10);
686  while (!exiting()
687  && (!image_.getWidth() || !image_.getHeight())
688  && (!info_ || info_->K[0] == 0.))
689  {
690  //ROS_INFO_THROTTLE(1, "waiting for a rectified image...");
691  spinOnce();
692  loop_rate.sleep();
693  }
694  }
695 
696  void
698  (const geometry_msgs::TransformStampedConstPtr& transform)
699  {
700  objectPositionHint_ = *transform;
701  }
702 
703 } // end of namespace visp_tracker.
void reconfigureKltCallbackAndInitViewer(ros::NodeHandle &nh, vpMbTracker *tracker, vpImage< unsigned char > &I, vpKltOpencv &kltTracker, boost::recursive_mutex &mutex, visp_tracker::ModelBasedSettingsKltConfig &config, uint32_t level)
Definition: callbacks.cpp:213
std::string rectifiedImageTopic_
Definition: tracker.hh:107
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
#define ROS_FATAL(...)
std::string convertVpMeToRosMessage(const vpMbTracker *tracker, const vpMe &moving_edge)
Definition: conversion.cpp:113
void transformToVpHomogeneousMatrix(vpHomogeneousMatrix &dst, const geometry_msgs::Transform &src)
Definition: conversion.cpp:167
void publish(const boost::shared_ptr< M > &message) const
f
image_transport::CameraSubscriber::Callback bindImageCallback(vpImage< unsigned char > &image)
Definition: callbacks.cpp:42
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsEdgeConfig >::reconfigureSrv_t * reconfigureEdgeSrv_
Definition: tracker.hh:118
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 convertVpKltOpencvToRosMessage(const vpMbTracker *tracker, const vpKltOpencv &klt)
Definition: conversion.cpp:134
void convertInitRequestToVpMbTracker(const visp_tracker::Init::Request &req, vpMbTracker *tracker)
Definition: conversion.cpp:232
std::string getName(void *handle)
image_proc::AdvertisementChecker checkInputs_
Helper used to check that subscribed topics exist.
Definition: tracker.hh:139
std_msgs::Header header_
Definition: tracker.hh:128
std::string cameraInfoTopic_
Definition: tracker.hh:108
std::string worldFrameId_
Definition: tracker.hh:144
ros::Publisher resultPublisher_
Definition: tracker.hh:120
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
ros::Publisher movingEdgeSitesPublisher_
Definition: tracker.hh:123
std::string init_service
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
std::string childFrameId_
Definition: tracker.hh:148
vpKltOpencv kltTracker_
Definition: tracker.hh:131
#define ROS_WARN(...)
Tracker(ros::NodeHandle &nh, ros::NodeHandle &privateNh, volatile bool &exiting, unsigned queueSize=5u)
boost::recursive_mutex mutex_
Definition: tracker.hh:114
image_transport::ImageTransport imageTransport_
Definition: tracker.hh:99
ros::Subscriber objectPositionHintSubscriber_
Definition: tracker.hh:150
boost::filesystem::path modelPath_
Definition: tracker.hh:110
void convertInitRequestToVpKltOpencv(const visp_tracker::Init::Request &req, vpMbTracker *tracker, vpKltOpencv &klt)
Definition: conversion.cpp:330
void callback(const sensor_msgs::ImageConstPtr &msg)
ros::NodeHandle & nodeHandle_
Definition: tracker.hh:97
bool initCallback(visp_tracker::Init::Request &req, visp_tracker::Init::Response &res)
std::vector< std::string > V_string
void convertInitRequestToVpMe(const visp_tracker::Init::Request &req, vpMbTracker *tracker, vpMe &moving_edge)
Definition: conversion.cpp:282
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsKltConfig >::reconfigureSrv_t * reconfigureKltSrv_
Definition: tracker.hh:117
#define ROS_WARN_THROTTLE(period,...)
unsigned queueSize_
Definition: tracker.hh:95
#define ROS_INFO(...)
geometry_msgs::TransformStamped objectPositionHint_
Definition: tracker.hh:151
bool param(const std::string &param_name, T &param_val, const T &default_val) const
std::string cameraPrefix_
Definition: tracker.hh:106
void reconfigureEdgeCallbackAndInitViewer(ros::NodeHandle &nh, vpMbTracker *tracker, vpImage< unsigned char > &I, vpMe &moving_edge, boost::recursive_mutex &mutex, visp_tracker::ModelBasedSettingsEdgeConfig &config, uint32_t level)
Definition: callbacks.cpp:201
image_transport::CameraSubscriber cameraSubscriber_
Definition: tracker.hh:112
vpMbTracker * tracker_
Definition: tracker.hh:134
void sendTransform(const StampedTransform &transform)
void reconfigureCallbackAndInitViewer(ros::NodeHandle &nh, vpMbTracker *tracker, vpImage< unsigned char > &I, vpMe &moving_edge, vpKltOpencv &kltTracker, boost::recursive_mutex &mutex, visp_tracker::ModelBasedSettingsConfig &config, uint32_t level)
Definition: callbacks.cpp:188
tf::TransformListener listener_
Definition: tracker.hh:143
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
sensor_msgs::CameraInfoConstPtr info_
Definition: tracker.hh:129
#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:136
uint32_t getNumSubscribers() const
void updateMovingEdgeSites(visp_tracker::MovingEdgeSitesPtr sites)
#define ROS_INFO_STREAM(args)
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsConfig >::reconfigureSrv_t * reconfigureSrv_
Definition: tracker.hh:116
tf::TransformBroadcaster transformBroadcaster_
Definition: tracker.hh:147
void initializeVpCameraFromCameraInfo(vpCameraParameters &cam, sensor_msgs::CameraInfoConstPtr info)
Definition: conversion.cpp:348
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:46
ros::ServiceServer initService_
Definition: tracker.hh:126
dynamic_reconfigure::Server< ConfigType > reconfigureSrv_t
Definition: tracker.hh:50
ROSCPP_DECL void shutdown()
std::string object_position_topic
vpCameraParameters cameraParameters_
Definition: tracker.hh:133
#define ROS_ERROR_STREAM(args)
volatile bool & exiting_
Definition: tracker.hh:93
void vpHomogeneousMatrixToTransform(geometry_msgs::Transform &dst, const vpHomogeneousMatrix &src)
Definition: conversion.cpp:151
std::string convertVpMbTrackerToRosMessage(const vpMbTracker *tracker)
Definition: conversion.cpp:87
std::string klt_points_topic
ros::NodeHandle & nodeHandlePrivate_
Definition: tracker.hh:98
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
#define ROS_DEBUG_THROTTLE(period,...)
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
std::string trackerType_
Definition: tracker.hh:102
ros::Publisher kltPointsPublisher_
Definition: tracker.hh:124
bool makeModelFile(boost::filesystem::ofstream &modelStream, std::string &fullModelPath)
Definition: file.cpp:62
vpHomogeneousMatrix cMo_
Definition: tracker.hh:141
#define ROS_DEBUG(...)
ros::Publisher transformationPublisher_
Definition: tracker.hh:121


visp_tracker
Author(s): Thomas Moulard
autogenerated on Wed Jul 3 2019 19:48:07