tracker-viewer.cpp
Go to the documentation of this file.
1 #include <cstdlib>
2 #include <fstream>
3 #include <sstream>
4 
5 #include <boost/bind.hpp>
6 #include <boost/filesystem.hpp>
7 #include <boost/filesystem/fstream.hpp>
8 #include <boost/filesystem/path.hpp>
9 #include <boost/format.hpp>
10 #include <boost/optional.hpp>
11 
12 #include <ros/ros.h>
13 #include <ros/param.h>
15 
16 #include <visp3/gui/vpDisplayX.h>
17 
18 #include "conversion.hh"
19 #include "callbacks.hh"
20 #include "file.hh"
21 #include "names.hh"
22 
23 #include "tracker-viewer.hh"
24 
25 namespace visp_tracker
26 {
27  namespace
28  {
29  static void increment(unsigned int* value)
30  {
31  ++(*value);
32  }
33  } // end of anonymous namespace.
34 
35  // Callback to fix ROS bug when /model_description (not properly cleared) doesn't contain the right model of the object to track.
36  // Bug only occurs when viewer is started too early and with a different model than the previous call.
37  bool
38  TrackerViewer::initCallback(visp_tracker::Init::Request& req,
39  visp_tracker::Init::Response& res)
40  {
41  boost::filesystem::ofstream modelStream;
42  std::string path;
43 
44  if (!makeModelFile(modelStream, path))
45  throw std::runtime_error("failed to load the model from the callback");
46  //ROS_WARN_STREAM("Make model Viewer: " << path.c_str());
47  ROS_INFO_STREAM("Model loaded from the service.");
48  modelPath_ = path;
49  tracker_.resetTracker();
51 
52  // Common parameters
54 
55  res.initialization_succeed = true;
56  return true;
57  }
58 
59  bool
60  TrackerViewer::reconfigureCallback(visp_tracker::Init::Request& req,
61  visp_tracker::Init::Response& res)
62  {
63  // Common parameters
64  ROS_INFO_STREAM("Reconfiguring Tracker Viewer.");
66 
67  res.initialization_succeed = true;
68  return true;
69  }
70 
72  ros::NodeHandle& privateNh,
73  volatile bool& exiting,
74  unsigned queueSize)
75  : exiting_ (exiting),
76  queueSize_(queueSize),
77  nodeHandle_(nh),
78  nodeHandlePrivate_(privateNh),
80  frameSize_(0.1),
83  checkInputs_(nodeHandle_, ros::this_node::getName()),
84  tracker_(),
86  image_(),
87  info_(),
88  initService_(),
90  trackerName_(),
91  cMo_(boost::none),
92  sites_(),
99  timer_(),
100  countAll_(0u),
101  countImages_(0u),
102  countCameraInfo_(0u),
105  countKltPoints_(0u)
106  {
107  // Compute topic and services names.
108  std::string cameraPrefix;
109 
110  ros::Rate rate (1);
111  while (cameraPrefix.empty ())
112  {
113  // Check for the global parameter /camera_prefix set by visp_tracker node
114  if (!nodeHandle_.getParam ("camera_prefix", cameraPrefix) && !ros::param::get ("~camera_prefix", cameraPrefix))
115  {
116  ROS_WARN
117  ("the camera_prefix parameter does not exist.\n"
118  "This may mean that:\n"
119  "- the tracker is not launched,\n"
120  "- the tracker and viewer are not running in the same namespace."
121  );
122  }
123  else if (cameraPrefix.empty ())
124  {
125  ROS_INFO
126  ("tracker is not yet initialized, waiting...\n"
127  "You may want to launch the client to initialize the tracker.");
128  }
129  if (this->exiting())
130  return;
131  rate.sleep ();
132  }
133  nodeHandlePrivate_.param<double>("frame_size", frameSize_, 0.1);
134 
136  ros::names::resolve(cameraPrefix + "/image_rect");
138  ros::names::resolve(cameraPrefix + "/camera_info");
139 
141  boost::bind(&TrackerViewer::initCallback, this, _1, _2);
142 
144  boost::bind(&TrackerViewer::reconfigureCallback, this, _1, _2);
145 
147  (visp_tracker::init_service_viewer, initCallback);
148 
150  (visp_tracker::reconfigure_service_viewer, reconfigureCallback);
151 
152 
153  boost::filesystem::ofstream modelStream;
154  std::string path;
155 
156  unsigned int cpt = 0;
158  {
160  {
161  if(cpt%10 == 0){
163  ("[Node: " << ros::this_node::getName() << "]\n"
164  "The model_description parameter does not exist.\n"
165  "This may mean that:\n"
166  "- the tracker is not launched or not initialized,\n"
167  "- the tracker and viewer are not running in the same namespace."
168  );
169  }
170  cpt++;
171  }
172  if (this->exiting())
173  return;
174  rate.sleep ();
175  }
176 
177 
178  if (!makeModelFile(modelStream, path))
179  throw std::runtime_error
180  ("failed to load the model from the parameter server");
181 
182  ROS_INFO_STREAM("Model loaded from the parameter server.");
183  //ROS_WARN_STREAM("Make model Viewer: " << path.c_str());
184  modelPath_ = path;
185 
187 
188  if (this->exiting())
189  return;
190 
191  checkInputs();
192  if (this->exiting())
193  return;
194 
195  // Subscribe to camera and tracker synchronously.
202  queueSize_);
207 
208  synchronizer_.connectInput
211  synchronizer_.registerCallback(boost::bind(&TrackerViewer::callback,
212  this, _1, _2, _3, _4, _5));
213 
214  // Check for synchronization every 30s.
215  synchronizer_.registerCallback(boost::bind(increment, &countAll_));
216  imageSubscriber_.registerCallback(boost::bind(increment, &countImages_));
218  (boost::bind(increment, &countCameraInfo_));
220  (boost::bind(increment, &countTrackingResult_));
222  (boost::bind(increment, &countMovingEdgeSites_));
224  (boost::bind(increment, &countKltPoints_));
225 
227  (ros::WallDuration(30.),
228  boost::bind(&TrackerViewer::timerCallback, this));
229 
230  // Wait for image.
231  waitForImage();
232  if (this->exiting())
233  return;
234  if (!image_.getWidth() || !image_.getHeight())
235  throw std::runtime_error("failed to retrieve image");
236 
237  // Load camera parameters.
239  tracker_.setCameraParameters(cameraParameters_);
240 
241  // Load the common parameters from ROS messages
243  }
244 
245  void
247  {
248  boost::format fmtWindowTitle ("ViSP MBT tracker viewer - [ns: %s]");
249  fmtWindowTitle % ros::this_node::getNamespace ();
250 
251  vpDisplayX d(image_,
252  image_.getWidth(), image_.getHeight(),
253  fmtWindowTitle.str().c_str());
254  vpImagePoint point (10, 10);
255  vpImagePoint pointTime (22, 10);
256  vpImagePoint pointCameraTopic (34, 10);
257  ros::Rate loop_rate(80);
258 
259  boost::format fmt("tracking (x=%f y=%f z=%f)");
260  boost::format fmtTime("time = %f");
261 
262  boost::format fmtCameraTopic("camera topic = %s");
263  fmtCameraTopic % rectifiedImageTopic_;
264  while (!exiting())
265  {
266  vpDisplay::display(image_);
269  if (cMo_)
270  {
271  try
272  {
273  tracker_.initFromPose(image_, *cMo_);
274  tracker_.display(image_, *cMo_, cameraParameters_, vpColor::red);
275  vpDisplay::displayFrame(image_, *cMo_, cameraParameters_, frameSize_, vpColor::none, 2);
276  }
277  catch(...)
278  {
279  ROS_DEBUG_STREAM_THROTTLE(10, "failed to display cmo");
280  }
281 
282  ROS_DEBUG_STREAM_THROTTLE(10, "cMo viewer:\n" << *cMo_);
283 
284  fmt % (*cMo_)[0][3] % (*cMo_)[1][3] % (*cMo_)[2][3];
285  vpDisplay::displayCharString
286  (image_, point, fmt.str().c_str(), vpColor::red);
287  fmtTime % info_->header.stamp.toSec();
288  vpDisplay::displayCharString
289  (image_, pointTime, fmtTime.str().c_str(), vpColor::red);
290  vpDisplay::displayCharString
291  (image_, pointCameraTopic, fmtCameraTopic.str().c_str(),
292  vpColor::red);
293  }
294  else{
295  vpDisplay::displayCharString
296  (image_, point, "tracking failed", vpColor::red);
297  }
298 
299  vpDisplay::flush(image_);
300  ros::spinOnce();
301  loop_rate.sleep();
302  }
303  }
304 
305  void
307  {
308  ros::Rate loop_rate(10);
309  while (!exiting()
310  && (!image_.getWidth() || !image_.getHeight()))
311  {
312  ROS_INFO_THROTTLE(1, "waiting for a rectified image...");
313  ros::spinOnce();
314  loop_rate.sleep();
315  }
316  }
317 
318  void
320  {
321  ros::V_string topics;
322  topics.push_back(rectifiedImageTopic_);
323  topics.push_back(cameraInfoTopic_);
324  topics.push_back(visp_tracker::object_position_topic);
325  topics.push_back(visp_tracker::moving_edge_sites_topic);
326  topics.push_back(visp_tracker::klt_points_topic);
327  checkInputs_.start(topics, 60.0);
328  }
329 
330  void
332  {
333  nodeHandlePrivate_.param<std::string>("tracker_name", trackerName_, "");
334  std::string key;
335 
336  bool loadParam = false;
337 
338  if(trackerName_.empty())
339  {
340  if(!ros::param::search("/angle_appear",key)){
341  trackerName_ = "tracker_mbt";
342  if(!ros::param::search(trackerName_ + "/angle_appear",key))
343  {
344  ROS_WARN_STREAM("No tracker has been found with the default name value \""
345  << trackerName_ << "/angle_appear\".\n"
346  << "Tracker name parameter (tracker_name) should be provided for this node (tracker_viewer).\n"
347  << "Polygon visibility might not work well in the viewer window.");
348  }
349  else loadParam = true;
350  }
351  else loadParam = true;
352  }
353  else loadParam = true;
354 
355  // Reading common parameters
356  if(loadParam)
357  {
358  if (ros::param::search(trackerName_ + "/angle_appear",key))
359  {
360  double value;
361  if(ros::param::get(key,value)){
362  // ROS_WARN_STREAM("Angle Appear Viewer: " << value);
363  tracker_.setAngleAppear(vpMath::rad(value));
364  }
365  }
366  else
367  {
368  ROS_WARN_STREAM("No tracker has been found with the provided parameter "
369  << "(tracker_name=\"" << trackerName_ << "\")\n"
370  << "Polygon visibility might not work well in the viewer window");
371  }
372 
373  if (ros::param::search(trackerName_ + "/angle_disappear",key))
374  {
375  double value;
376  if(ros::param::get(key,value)){
377  // ROS_WARN_STREAM("Angle Disappear Viewer: " << value);
378  tracker_.setAngleDisappear(vpMath::rad(value));
379  }
380  }
381  }
382  }
383 
384  void
386  {
387  try
388  {
389  // ROS_WARN_STREAM("Trying to load the model Viewer: " << modelPath_);
390  tracker_.loadModel(modelPath_.native().c_str());
391  }
392  catch(...)
393  {
394  boost::format fmt("failed to load the model %1%");
395  fmt % modelPath_;
396  throw std::runtime_error(fmt.str());
397  }
398  // ROS_WARN("Model has been successfully loaded.");
399  }
400 
401  void
403  (const sensor_msgs::ImageConstPtr& image,
404  const sensor_msgs::CameraInfoConstPtr& info,
405  const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& trackingResult,
406  const visp_tracker::MovingEdgeSites::ConstPtr& sites,
407  const visp_tracker::KltPoints::ConstPtr& klt)
408  {
409  // Copy image.
410  try
411  {
412  rosImageToVisp(image_, image);
413  }
414  catch(std::exception& e)
415  {
416  ROS_ERROR_STREAM("dropping frame: " << e.what());
417  }
418 
419  // Copy moving camera infos, edges sites and optional KLT points.
420  info_ = info;
421  sites_ = sites;
422  klt_ = klt;
423 
424  // Copy cMo.
425  cMo_ = vpHomogeneousMatrix();
426  transformToVpHomogeneousMatrix(*cMo_, trackingResult->pose.pose);
427  }
428 
429  void
431  {
432  if (!sites_)
433  return;
434  for (unsigned i = 0; i < sites_->moving_edge_sites.size(); ++i)
435  {
436  double x = sites_->moving_edge_sites[i].x;
437  double y = sites_->moving_edge_sites[i].y;
438  int suppress = sites_->moving_edge_sites[i].suppress;
439  vpColor color = vpColor::black;
440 
441  switch(suppress)
442  {
443  case vpMeSite::NO_SUPPRESSION:
444  color = vpColor::green;
445  break;
446  case vpMeSite::CONSTRAST:
447  color = vpColor::blue;
448  break;
449  case vpMeSite::THRESHOLD:
450  color = vpColor::purple;
451  break;
452  case vpMeSite::M_ESTIMATOR:
453  color = vpColor::red;
454  break;
455  default: // vpMeSite::UNKOWN
456  color = vpColor::yellow;
457  }
458 
459  vpDisplay::displayCross(image_, vpImagePoint(x, y), 3, color, 1);
460  }
461  }
462 
463 
464  void
466  {
467  if (!klt_)
468  return;
469  vpImagePoint pos;
470 
471  for (unsigned i = 0; i < klt_->klt_points_positions.size(); ++i)
472  {
473  double ii = klt_->klt_points_positions[i].i;
474  double jj = klt_->klt_points_positions[i].j;
475  int id = klt_->klt_points_positions[i].id;
476  vpColor color = vpColor::red;
477 
478  vpDisplay::displayCross(image_, vpImagePoint(ii, jj), 15, color, 1);
479 
480  pos.set_i( vpMath::round( ii + 7 ) );
481  pos.set_j( vpMath::round( jj + 7 ) );
482  char ide[10];
483  sprintf(ide, "%d", id);
484  vpDisplay::displayCharString(image_, pos, ide, vpColor::red);
485  }
486  }
487 
488  void
490  {
493  {
494  boost::format fmt
495  ("[visp_tracker] Low number of synchronized tuples received.\n"
496  "Images: %d\n"
497  "Camera info: %d\n"
498  "Tracking result: %d\n"
499  "Moving edge sites: %d\n"
500  "KLT points: %d\n"
501  "Synchronized tuples: %d\n"
502  "Possible issues:\n"
503  "\t* The network is too slow.");
506  ROS_WARN_STREAM_THROTTLE(10, fmt.str());
507  }
508  }
509 } // end of namespace visp_tracker.
d
image_transport::ImageTransport imageTransport_
Image transport used to receive images.
ros::NodeHandle & nodeHandle_
#define ROS_DEBUG_STREAM_THROTTLE(rate, args)
void transformToVpHomogeneousMatrix(vpHomogeneousMatrix &dst, const geometry_msgs::Transform &src)
Definition: conversion.cpp:138
void displayMovingEdgeSites()
Display moving edge sites.
void waitForImage()
Hang until the first image is received.
message_filters::Subscriber< geometry_msgs::PoseWithCovarianceStamped > trackingResultSubscriber_
Subscriber to tracking result topic.
std::string rectifiedImageTopic_
Full topic name for rectified image.
void start(const ros::V_string &topics, double duration)
std::string moving_edge_sites_topic
boost::function< bool(visp_tracker::Init::Request &, visp_tracker::Init::Response &res)> initCallback_t
std::string getName(void *handle)
boost::function< bool(visp_tracker::Init::Request &, visp_tracker::Init::Response &res)> reconfigureCallback_t
ros::ServiceServer reconfigureService_
Service called when user is reconfiguring tracker node.
ROSCPP_DECL const std::string & getName()
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
TFSIMD_FORCE_INLINE const tfScalar & y() const
#define ROS_WARN(...)
vpMbGenericTracker tracker_
ViSP edge tracker.
message_filters::Subscriber< visp_tracker::KltPoints > kltPointsSubscriber_
Subscriber to KLT point topics.
visp_tracker::KltPoints::ConstPtr klt_
Shared pointer to latest received KLT point positions.
image_proc::AdvertisementChecker checkInputs_
Helper used to check that subscribed topics exist.
std::string trackerName_
Name of the tracker used in this viewer node.
TrackerViewer(ros::NodeHandle &nh, ros::NodeHandle &privateNh, volatile bool &exiting, unsigned queueSize=5u)
Constructor.
ros::NodeHandle & nodeHandlePrivate_
std::vector< std::string > V_string
void displayKltPoints()
Display KLT points that are tracked.
boost::filesystem::path modelPath_
Model path.
ROSCPP_DECL const std::string & getNamespace()
ROSCPP_DECL bool get(const std::string &key, std::string &s)
image_t image_
ViSP image.
#define ROS_INFO(...)
bool initCallback(visp_tracker::Init::Request &req, visp_tracker::Init::Response &res)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
std::string model_description_param
bool reconfigureCallback(visp_tracker::Init::Request &req, visp_tracker::Init::Response &res)
void callback(const sensor_msgs::ImageConstPtr &imageConst, const sensor_msgs::CameraInfoConstPtr &infoConst, const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &trackingResult, const visp_tracker::MovingEdgeSites::ConstPtr &sitesConst, const visp_tracker::KltPoints::ConstPtr &kltConst)
Callback used to received synchronized data.
sensor_msgs::CameraInfoConstPtr info_
Shared pointer to latest received camera information.
WallTimer createWallTimer(WallDuration period, void(T::*callback)(const WallTimerEvent &), T *obj, bool oneshot=false, bool autostart=true) const
TFSIMD_FORCE_INLINE const tfScalar & x() const
std::string reconfigure_service_viewer
#define ROS_WARN_STREAM(args)
image_transport::SubscriberFilter imageSubscriber_
bool sleep()
ros::ServiceServer initService_
Service called when user ends tracker_client node.
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
#define ROS_WARN_STREAM_THROTTLE(rate, args)
void checkInputs()
Make sure the topics we subscribe already exist.
message_filters::Synchronizer< syncPolicy_t > synchronizer_
Synchronizer with approximate time policy.
vpCameraParameters cameraParameters_
ViSP camera parameters.
message_filters::Subscriber< visp_tracker::MovingEdgeSites > movingEdgeSitesSubscriber_
Subscriber to moving edge sites topics.
void initializeTracker()
Initialize the tracker.
unsigned queueSize_
Queue size for all subscribers.
#define ROS_INFO_STREAM(args)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
std::string cameraInfoTopic_
Full topic name for camera information.
boost::optional< vpHomogeneousMatrix > cMo_
Last tracked object position, set to none if tracking failed.
bool getParam(const std::string &key, std::string &s) const
void initializeVpCameraFromCameraInfo(vpCameraParameters &cam, sensor_msgs::CameraInfoConstPtr info)
Definition: conversion.cpp:256
std::string object_position_covariance_topic
void spin()
Display camera image, tracked object position and moving edge sites.
#define ROS_INFO_THROTTLE(rate,...)
std::string init_service_viewer
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSubscriber_
Subscriber to camera information topic.
std::string object_position_topic
void convertInitRequestToVpMbTracker(const visp_tracker::Init::Request &req, vpMbGenericTracker &tracker)
Definition: conversion.cpp:186
bool hasParam(const std::string &key) const
#define ROS_ERROR_STREAM(args)
std::string klt_points_topic
ROSCPP_DECL void spinOnce()
ROSCPP_DECL bool search(const std::string &ns, const std::string &key, std::string &result)
visp_tracker::MovingEdgeSites::ConstPtr sites_
Shared pointer to latest received moving edge sites.
bool makeModelFile(boost::filesystem::ofstream &modelStream, std::string &fullModelPath)
Definition: file.cpp:62
void increment(int *value)
Connection registerCallback(const C &callback)
void loadCommonParameters()
Initialize the common parameters (visibility angles, etc)
void rosImageToVisp(vpImage< unsigned char > &dst, const sensor_msgs::Image::ConstPtr &src)
Convert a ROS image into a ViSP one.
Definition: conversion.cpp:21


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