leg_detector.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 #include <ros/ros.h>
35 
36 #include <leg_detector/LegDetectorConfig.h>
39 
40 #include <opencv/cxcore.h>
41 #include <opencv/cv.h>
42 #include <opencv/ml.h>
43 
44 #include <people_msgs/PositionMeasurement.h>
45 #include <people_msgs/PositionMeasurementArray.h>
46 #include <sensor_msgs/LaserScan.h>
47 
48 #include <tf/transform_listener.h>
49 #include <tf/message_filter.h>
51 
55 #include <visualization_msgs/Marker.h>
56 #include <dynamic_reconfigure/server.h>
57 
58 #include <algorithm>
59 #include <list>
60 #include <set>
61 #include <string>
62 #include <vector>
63 
64 static double no_observation_timeout_s = 0.5;
65 static double max_second_leg_age_s = 2.0;
66 static double max_track_jump_m = 1.0;
67 static double max_meas_jump_m = 0.75; // 1.0
68 static double leg_pair_separation_m = 1.0;
69 static std::string fixed_frame = "odom_combined";
70 
71 static double kal_p = 4, kal_q = .002, kal_r = 10;
72 static bool use_filter = true;
73 
74 
76 {
77 public:
78  static int nextid;
80 
83 
84  std::string id_;
85  std::string object_id;
88 
89  double reliability, p;
90 
94 
95  // one leg tracker
97  : tfl_(tfl),
98  sys_sigma_(tf::Vector3(0.05, 0.05, 0.05), tf::Vector3(1.0, 1.0, 1.0)),
99  filter_("tracker_name", sys_sigma_),
100  reliability(-1.), p(4)
101  {
102  char id[100];
103  snprintf(id, sizeof(id), "legtrack%d", nextid++);
104  id_ = std::string(id);
105 
106  object_id = "";
107  time_ = loc.stamp_;
108  meas_time_ = loc.stamp_;
109  other = NULL;
110 
111  try
112  {
113  tfl_.transformPoint(fixed_frame, loc, loc);
114  }
115  catch (...)
116  {
117  ROS_WARN("TF exception spot 6.");
118  }
119  tf::StampedTransform pose(tf::Pose(tf::Quaternion(0.0, 0.0, 0.0, 1.0), loc), loc.stamp_, id_, loc.frame_id_);
120  tfl_.setTransform(pose);
121 
122  BFL::StatePosVel prior_sigma(tf::Vector3(0.1, 0.1, 0.1), tf::Vector3(0.0000001, 0.0000001, 0.0000001));
123  filter_.initialize(loc, prior_sigma, time_.toSec());
124 
125  BFL::StatePosVel est;
126  filter_.getEstimate(est);
127 
128  updatePosition();
129  }
130 
131  void propagate(ros::Time time)
132  {
133  time_ = time;
134 
135  filter_.updatePrediction(time.toSec());
136 
137  updatePosition();
138  }
139 
140  void update(tf::Stamped<tf::Point> loc, double probability)
141  {
142  tf::StampedTransform pose(tf::Pose(tf::Quaternion(0.0, 0.0, 0.0, 1.0), loc), loc.stamp_, id_, loc.frame_id_);
143  tfl_.setTransform(pose);
144 
145  meas_time_ = loc.stamp_;
146  time_ = meas_time_;
147 
148  MatrixWrapper::SymmetricMatrix cov(3);
149  cov = 0.0;
150  cov(1, 1) = 0.0025;
151  cov(2, 2) = 0.0025;
152  cov(3, 3) = 0.0025;
153 
154  filter_.updateCorrection(loc, cov);
155 
156  updatePosition();
157 
158  if (reliability < 0 || !use_filter)
159  {
160  reliability = probability;
161  p = kal_p;
162  }
163  else
164  {
165  p += kal_q;
166  double k = p / (p + kal_r);
167  reliability += k * (probability - reliability);
168  p *= (1 - k);
169  }
170  }
171 
172  double getLifetime()
173  {
174  return filter_.getLifetime();
175  }
176 
177  double getReliability()
178  {
179  return reliability;
180  }
181 
182 private:
184  {
185  BFL::StatePosVel est;
186  filter_.getEstimate(est);
187 
188  position_[0] = est.pos_[0];
189  position_[1] = est.pos_[1];
190  position_[2] = est.pos_[2];
191  position_.stamp_ = time_;
192  position_.frame_id_ = fixed_frame;
193  double nreliability = fmin(1.0, fmax(0.1, est.vel_.length() / 0.5));
194  // reliability = fmax(reliability, nreliability);
195  }
196 };
197 
198 int SavedFeature::nextid = 0;
199 
200 
201 
202 
204 {
205 public:
208  float distance_;
209  double probability_;
210 
211  MatchedFeature(laser_processor::SampleSet* candidate, SavedFeature* closest, float distance, double probability)
212  : candidate_(candidate)
213  , closest_(closest)
214  , distance_(distance)
215  , probability_(probability)
216  {}
217 
218  inline bool operator< (const MatchedFeature& b) const
219  {
220  return (distance_ < b.distance_);
221  }
222 };
223 
224 int g_argc;
225 char** g_argv;
226 
227 
228 
229 
230 // actual legdetector node
232 {
233 public:
235 
237 
239 
241 
242  // cv::ml::RTrees forest;
243  cv::Ptr<cv::ml::RTrees> forest;
244 
246 
248 
249  char save_[100];
250 
251  std::list<SavedFeature*> saved_features_;
252  boost::mutex saved_mutex_;
253 
255 
257  bool publish_legs_, publish_people_, publish_leg_markers_, publish_people_markers_;
261 
265 
266  dynamic_reconfigure::Server<leg_detector::LegDetectorConfig> server_;
267 
272 
274  nh_(nh),
275  mask_count_(0),
276  feat_count_(0),
277  next_p_id_(0),
278  people_sub_(nh_, "people_tracker_filter", 10),
279  laser_sub_(nh_, "scan", 10),
280  people_notifier_(people_sub_, tfl_, fixed_frame, 10),
281  laser_notifier_(laser_sub_, tfl_, fixed_frame, 10)
282  {
283  if (g_argc > 1)
284  {
285  forest = cv::ml::RTrees::create();
286  cv::String feature_file = cv::String(g_argv[1]);
287  forest = cv::ml::StatModel::load<cv::ml::RTrees>(feature_file);
288  feat_count_ = forest->getVarCount();
289  printf("Loaded forest with %d features: %s\n", feat_count_, g_argv[1]);
290  }
291  else
292  {
293  printf("Please provide a trained random forests classifier as an input.\n");
294  ros::shutdown();
295  }
296 
297  nh_.param<bool>("use_seeds", use_seeds_, !true);
298 
299  // advertise topics
300  leg_measurements_pub_ = nh_.advertise<people_msgs::PositionMeasurementArray>("leg_tracker_measurements", 0);
301  people_measurements_pub_ = nh_.advertise<people_msgs::PositionMeasurementArray>("people_tracker_measurements", 0);
302  markers_pub_ = nh_.advertise<visualization_msgs::Marker>("visualization_marker", 20);
303 
304  if (use_seeds_)
305  {
306  people_notifier_.registerCallback(boost::bind(&LegDetector::peopleCallback, this, _1));
307  people_notifier_.setTolerance(ros::Duration(0.01));
308  }
309  laser_notifier_.registerCallback(boost::bind(&LegDetector::laserCallback, this, _1));
310  laser_notifier_.setTolerance(ros::Duration(0.01));
311 
312  dynamic_reconfigure::Server<leg_detector::LegDetectorConfig>::CallbackType f;
313  f = boost::bind(&LegDetector::configure, this, _1, _2);
314  server_.setCallback(f);
315 
316  feature_id_ = 0;
317  }
318 
319 
321  {
322  }
323 
324  void configure(leg_detector::LegDetectorConfig &config, uint32_t level)
325  {
326  connected_thresh_ = config.connection_threshold;
327  min_points_per_group = config.min_points_per_group;
328  leg_reliability_limit_ = config.leg_reliability_limit;
329  publish_legs_ = config.publish_legs;
330  publish_people_ = config.publish_people;
331  publish_leg_markers_ = config.publish_leg_markers;
332  publish_people_markers_ = config.publish_people_markers;
333 
334  no_observation_timeout_s = config.no_observation_timeout;
335  max_second_leg_age_s = config.max_second_leg_age;
336  max_track_jump_m = config.max_track_jump;
337  max_meas_jump_m = config.max_meas_jump;
338  leg_pair_separation_m = config.leg_pair_separation;
339  if (fixed_frame.compare(config.fixed_frame) != 0)
340  {
341  fixed_frame = config.fixed_frame;
342  laser_notifier_.setTargetFrame(fixed_frame);
343  people_notifier_.setTargetFrame(fixed_frame);
344  }
345 
346  kal_p = config.kalman_p;
347  kal_q = config.kalman_q;
348  kal_r = config.kalman_r;
349  use_filter = config.kalman_on == 1;
350  }
351 
352  double distance(std::list<SavedFeature*>::iterator it1, std::list<SavedFeature*>::iterator it2)
353  {
354  tf::Stamped<tf::Point> one = (*it1)->position_, two = (*it2)->position_;
355  double dx = one[0] - two[0], dy = one[1] - two[1], dz = one[2] - two[2];
356  return sqrt(dx * dx + dy * dy + dz * dz);
357  }
358 
359  // Find the tracker that is closest to this person message
360  // If a tracker was already assigned to a person,
361  // keep this assignment when the distance between them is not too large.
362  void peopleCallback(const people_msgs::PositionMeasurement::ConstPtr& people_meas)
363  {
364  // If there are no legs, return.
365  if (saved_features_.empty())
366  return;
367 
368  tf::Point pt;
369  pointMsgToTF(people_meas->pos, pt);
370  tf::Stamped<tf::Point> person_loc(pt, people_meas->header.stamp, people_meas->header.frame_id);
371  person_loc[2] = 0.0; // Ignore the height of the person measurement.
372 
373  // Holder for all transformed pts.
374  tf::Stamped<tf::Point> dest_loc(pt, people_meas->header.stamp, people_meas->header.frame_id);
375 
376  boost::mutex::scoped_lock lock(saved_mutex_);
377 
378  std::list<SavedFeature*>::iterator closest = saved_features_.end();
379  std::list<SavedFeature*>::iterator closest1 = saved_features_.end();
380  std::list<SavedFeature*>::iterator closest2 = saved_features_.end();
381  float closest_dist = max_meas_jump_m;
382  float closest_pair_dist = 2 * max_meas_jump_m;
383 
384  std::list<SavedFeature*>::iterator begin = saved_features_.begin();
385  std::list<SavedFeature*>::iterator end = saved_features_.end();
386  std::list<SavedFeature*>::iterator it1, it2;
387 
388  // If there's a pair of legs with the right label and within the max dist, return
389  // If there's one leg with the right label and within the max dist,
390  // find a partner for it from the unlabeled legs whose tracks are reasonably new.
391  // If no partners exist, label just the one leg.
392  // If there are no legs with the right label and within the max dist,
393  // find a pair of unlabeled legs and assign them the label.
394  // If all of the above cases fail,
395  // find a new unlabeled leg and assign the label.
396 
397  // For each tracker, get the distance to this person.
398  for (it1 = begin; it1 != end; ++it1)
399  {
400  try
401  {
402  tfl_.transformPoint((*it1)->id_, people_meas->header.stamp,
403  person_loc, fixed_frame, dest_loc);
404  // ROS_INFO("Succesful leg transformation at spot 7");
405  }
406  catch (...)
407  {
408  ROS_WARN("TF exception spot 7.");
409  }
410  (*it1)->dist_to_person_ = dest_loc.length();
411  }
412 
413  // Try to find one or two trackers with the same label and within the max distance of the person.
414  std::cout << "Looking for two legs" << std::endl;
415  it2 = end;
416  for (it1 = begin; it1 != end; ++it1)
417  {
418  // If this leg belongs to the person...
419  if ((*it1)->object_id == people_meas->object_id)
420  {
421  // and their distance is close enough...
422  if ((*it1)->dist_to_person_ < max_meas_jump_m)
423  {
424  // if this is the first leg we've found, assign it to it2. Otherwise, leave it assigned to it1 and break.
425  if (it2 == end)
426  it2 = it1;
427  else
428  break;
429  }
430  // Otherwise, remove the tracker's label, it doesn't belong to this person.
431  else
432  {
433  // the two trackers moved apart. This should not happen.
434  (*it1)->object_id = "";
435  }
436  }
437  }
438  // If we found two legs with the right label and within the max distance, all is good, return.
439  if (it1 != end && it2 != end)
440  {
441  std::cout << "Found matching pair. The second distance was " << (*it1)->dist_to_person_ << std::endl;
442  return;
443  }
444 
445 
446 
447  // If we only found one close leg with the right label, let's try to find a second leg that
448  // * doesn't yet have a label (=valid precondition),
449  // * is within the max distance,
450  // * is less than max_second_leg_age_s old.
451  std::cout << "Looking for one leg plus one new leg" << std::endl;
452  float dist_between_legs, closest_dist_between_legs;
453  if (it2 != end)
454  {
455  closest_dist = max_meas_jump_m;
456  closest = saved_features_.end();
457 
458  for (it1 = begin; it1 != end; ++it1)
459  {
460  // Skip this leg track if:
461  // - you're already using it.
462  // - it already has an id.
463  // - it's too old. Old unassigned trackers are unlikely to be the second leg in a pair.
464  // - it's too far away from the person.
465  if ((it1 == it2) || ((*it1)->object_id != "") || ((*it1)->getLifetime() > max_second_leg_age_s) ||
466  ((*it1)->dist_to_person_ >= closest_dist))
467  continue;
468 
469  // Get the distance between the two legs
470  try
471  {
472  tfl_.transformPoint((*it1)->id_, (*it2)->position_.stamp_, (*it2)->position_, fixed_frame, dest_loc);
473  }
474  catch (...)
475  {
476  ROS_WARN("TF exception getting distance between legs.");
477  }
478  dist_between_legs = dest_loc.length();
479 
480  // If this is the closest dist (and within range), and the legs are close together and unlabeled, mark it.
481  if (dist_between_legs < leg_pair_separation_m)
482  {
483  closest = it1;
484  closest_dist = (*it1)->dist_to_person_;
485  closest_dist_between_legs = dist_between_legs;
486  }
487  }
488  // If we found a close, unlabeled leg, set it's label.
489  if (closest != end)
490  {
491  std::cout << "Replaced one leg with a distance of " << closest_dist
492  << " and a distance between the legs of " << closest_dist_between_legs << std::endl;
493  (*closest)->object_id = people_meas->object_id;
494  }
495  else
496  {
497  std::cout << "Returned one matched leg only" << std::endl;
498  }
499 
500  // Regardless of whether we found a second leg, return.
501  return;
502  }
503 
504  std::cout << "Looking for a pair of new legs" << std::endl;
505  // If we didn't find any legs with this person's label,
506  // try to find two unlabeled legs that are close together and close to the tracker.
507  it1 = saved_features_.begin();
508  it2 = saved_features_.begin();
509  closest = saved_features_.end();
510  closest1 = saved_features_.end();
511  closest2 = saved_features_.end();
512  closest_dist = max_meas_jump_m;
513  closest_pair_dist = 2 * max_meas_jump_m;
514  for (; it1 != end; ++it1)
515  {
516  // Only look at trackers without ids and that are not too far away.
517  if ((*it1)->object_id != "" || (*it1)->dist_to_person_ >= max_meas_jump_m)
518  continue;
519 
520  // Keep the single closest leg around in case none of the pairs work out.
521  if ((*it1)->dist_to_person_ < closest_dist)
522  {
523  closest_dist = (*it1)->dist_to_person_;
524  closest = it1;
525  }
526 
527  // Find a second leg.
528  it2 = it1;
529  it2++;
530  for (; it2 != end; ++it2)
531  {
532  // Only look at trackers without ids and that are not too far away.
533  if ((*it2)->object_id != "" || (*it2)->dist_to_person_ >= max_meas_jump_m)
534  continue;
535 
536  // Get the distance between the two legs
537  try
538  {
539  tfl_.transformPoint((*it1)->id_, (*it2)->position_.stamp_, (*it2)->position_, fixed_frame, dest_loc);
540  }
541  catch (...)
542  {
543  ROS_WARN("TF exception getting distance between legs in spot 2.");
544  }
545  dist_between_legs = dest_loc.length();
546 
547  // Ensure that this pair of legs is the closest pair to the tracker,
548  // and that the distance between the legs isn't too large.
549  if ((*it1)->dist_to_person_ + (*it2)->dist_to_person_ < closest_pair_dist &&
550  dist_between_legs < leg_pair_separation_m)
551  {
552  closest_pair_dist = (*it1)->dist_to_person_ + (*it2)->dist_to_person_;
553  closest1 = it1;
554  closest2 = it2;
555  closest_dist_between_legs = dist_between_legs;
556  }
557  }
558  }
559  // Found a pair of legs.
560  if (closest1 != end && closest2 != end)
561  {
562  (*closest1)->object_id = people_meas->object_id;
563  (*closest2)->object_id = people_meas->object_id;
564  std::cout << "Found a completely new pair with total distance " << closest_pair_dist
565  << " and a distance between the legs of " << closest_dist_between_legs << std::endl;
566  return;
567  }
568 
569  std::cout << "Looking for just one leg" << std::endl;
570  // No pair worked, try for just one leg.
571  if (closest != end)
572  {
573  (*closest)->object_id = people_meas->object_id;
574  std::cout << "Returned one new leg only" << std::endl;
575  return;
576  }
577 
578  std::cout << "Nothing matched" << std::endl;
579  }
580 
581  void pairLegs()
582  {
583  // Deal With legs that already have ids
584  std::list<SavedFeature*>::iterator begin = saved_features_.begin();
585  std::list<SavedFeature*>::iterator end = saved_features_.end();
586  std::list<SavedFeature*>::iterator leg1, leg2, best, it;
587 
588  for (leg1 = begin; leg1 != end; ++leg1)
589  {
590  // If this leg has no id, skip
591  if ((*leg1)->object_id == "")
592  continue;
593 
594  leg2 = end;
595  best = end;
596  double closest_dist = leg_pair_separation_m;
597  for (it = begin; it != end; ++it)
598  {
599  if (it == leg1) continue;
600 
601  if ((*it)->object_id == (*leg1)->object_id)
602  {
603  leg2 = it;
604  break;
605  }
606 
607  if ((*it)->object_id != "")
608  continue;
609 
610  double d = distance(it, leg1);
611  if (((*it)->getLifetime() <= max_second_leg_age_s)
612  && (d < closest_dist))
613  {
614  closest_dist = d;
615  best = it;
616  }
617  }
618 
619  if (leg2 != end)
620  {
621  double dist_between_legs = distance(leg1, leg2);
622  if (dist_between_legs > leg_pair_separation_m)
623  {
624  (*leg1)->object_id = "";
625  (*leg1)->other = NULL;
626  (*leg2)->object_id = "";
627  (*leg2)->other = NULL;
628  }
629  else
630  {
631  (*leg1)->other = *leg2;
632  (*leg2)->other = *leg1;
633  }
634  }
635  else if (best != end)
636  {
637  (*best)->object_id = (*leg1)->object_id;
638  (*leg1)->other = *best;
639  (*best)->other = *leg1;
640  }
641  }
642 
643  // Attempt to pair up legs with no id
644  for (;;)
645  {
646  std::list<SavedFeature*>::iterator best1 = end, best2 = end;
647  double closest_dist = leg_pair_separation_m;
648 
649  for (leg1 = begin; leg1 != end; ++leg1)
650  {
651  // If this leg has an id or low reliability, skip
652  if ((*leg1)->object_id != ""
653  || (*leg1)->getReliability() < leg_reliability_limit_)
654  continue;
655 
656  for (leg2 = begin; leg2 != end; ++leg2)
657  {
658  if (((*leg2)->object_id != "")
659  || ((*leg2)->getReliability() < leg_reliability_limit_)
660  || (leg1 == leg2)) continue;
661  double d = distance(leg1, leg2);
662  if (d < closest_dist)
663  {
664  best1 = leg1;
665  best2 = leg2;
666  }
667  }
668  }
669 
670  if (best1 != end)
671  {
672  char id[100];
673  snprintf(id, sizeof(id), "Person%d", next_p_id_++);
674  (*best1)->object_id = std::string(id);
675  (*best2)->object_id = std::string(id);
676  (*best1)->other = *best2;
677  (*best2)->other = *best1;
678  }
679  else
680  {
681  break;
682  }
683  }
684  }
685 
686  void laserCallback(const sensor_msgs::LaserScan::ConstPtr& scan)
687  {
688  laser_processor::ScanProcessor processor(*scan, mask_);
689 
690  processor.splitConnected(connected_thresh_);
691  processor.removeLessThan(5);
692 
693  cv::Mat tmp_mat = cv::Mat(1, feat_count_, CV_32FC1);
694 
695  // if no measurement matches to a tracker in the last <no_observation_timeout> seconds: erase tracker
696  ros::Time purge = scan->header.stamp + ros::Duration().fromSec(-no_observation_timeout_s);
697  std::list<SavedFeature*>::iterator sf_iter = saved_features_.begin();
698  while (sf_iter != saved_features_.end())
699  {
700  if ((*sf_iter)->meas_time_ < purge)
701  {
702  if ((*sf_iter)->other)
703  (*sf_iter)->other->other = NULL;
704  delete *sf_iter;
705  saved_features_.erase(sf_iter++);
706  }
707  else
708  ++sf_iter;
709  }
710 
711 
712  // System update of trackers, and copy updated ones in propagate list
713  std::list<SavedFeature*> propagated;
714  for (std::list<SavedFeature*>::iterator sf_iter = saved_features_.begin();
715  sf_iter != saved_features_.end();
716  sf_iter++)
717  {
718  (*sf_iter)->propagate(scan->header.stamp);
719  propagated.push_back(*sf_iter);
720  }
721 
722 
723  // Detection step: build up the set of "candidate" clusters
724  // For each candidate, find the closest tracker (within threshold) and add to the match list
725  // If no tracker is found, start a new one
726  std::multiset<MatchedFeature> matches;
727  for (std::list<laser_processor::SampleSet*>::iterator i = processor.getClusters().begin();
728  i != processor.getClusters().end();
729  i++)
730  {
731  std::vector<float> f = calcLegFeatures(*i, *scan);
732 
733  memcpy(tmp_mat.data, f.data(), f.size()*sizeof(float));
734 
735  // Probability is the fuzzy measure of the probability that the second element should be chosen,
736  // in opencv2 RTrees had a method predict_prob, but that disapeared in opencv3, this is the
737  // substitute.
738 
739  cv::Mat votes;
740 
741  forest->getVotes(tmp_mat, votes, 0);
742  // first row of columns cotains class labels. Here -1 and 1.
743  // second row then contains the number of trees voting for this class.
744  float probability = static_cast<float>(votes.at<int>(1, 1)) / static_cast<float>(forest->getRoots().size());
745 
746  tf::Stamped<tf::Point> loc((*i)->center(), scan->header.stamp, scan->header.frame_id);
747  try
748  {
749  tfl_.transformPoint(fixed_frame, loc, loc);
750  }
751  catch (...)
752  {
753  ROS_WARN("TF exception spot 3.");
754  }
755 
756  std::list<SavedFeature*>::iterator closest = propagated.end();
757  float closest_dist = max_track_jump_m;
758 
759  for (std::list<SavedFeature*>::iterator pf_iter = propagated.begin();
760  pf_iter != propagated.end();
761  pf_iter++)
762  {
763  // find the closest distance between candidate and trackers
764  float dist = loc.distance((*pf_iter)->position_);
765  if (dist < closest_dist)
766  {
767  closest = pf_iter;
768  closest_dist = dist;
769  }
770  }
771  // Nothing close to it, start a new track
772  if (closest == propagated.end())
773  {
774  std::list<SavedFeature*>::iterator new_saved =
775  saved_features_.insert(saved_features_.end(), new SavedFeature(loc, tfl_));
776  }
777  // Add the candidate, the tracker and the distance to a match list
778  else
779  matches.insert(MatchedFeature(*i, *closest, closest_dist, probability));
780  }
781 
782  // loop through _sorted_ matches list
783  // find the match with the shortest distance for each tracker
784  while (matches.size() > 0)
785  {
786  std::multiset<MatchedFeature>::iterator matched_iter = matches.begin();
787  bool found = false;
788  std::list<SavedFeature*>::iterator pf_iter = propagated.begin();
789  while (pf_iter != propagated.end())
790  {
791  // update the tracker with this candidate
792  if (matched_iter->closest_ == *pf_iter)
793  {
794  // Transform candidate to fixed frame
795  tf::Stamped<tf::Point> loc(matched_iter->candidate_->center(), scan->header.stamp, scan->header.frame_id);
796  try
797  {
798  tfl_.transformPoint(fixed_frame, loc, loc);
799  }
800  catch (...)
801  {
802  ROS_WARN("TF exception spot 4.");
803  }
804 
805  // Update the tracker with the candidate location
806  matched_iter->closest_->update(loc, matched_iter->probability_);
807 
808  // remove this match and
809  matches.erase(matched_iter);
810  propagated.erase(pf_iter++);
811  found = true;
812  break;
813  }
814  // still looking for the tracker to update
815  else
816  {
817  pf_iter++;
818  }
819  }
820 
821  // didn't find tracker to update, because it was deleted above
822  // try to assign the candidate to another tracker
823  if (!found)
824  {
825  tf::Stamped<tf::Point> loc(matched_iter->candidate_->center(), scan->header.stamp, scan->header.frame_id);
826  try
827  {
828  tfl_.transformPoint(fixed_frame, loc, loc);
829  }
830  catch (...)
831  {
832  ROS_WARN("TF exception spot 5.");
833  }
834 
835  std::list<SavedFeature*>::iterator closest = propagated.end();
836  float closest_dist = max_track_jump_m;
837 
838  for (std::list<SavedFeature*>::iterator remain_iter = propagated.begin();
839  remain_iter != propagated.end();
840  remain_iter++)
841  {
842  float dist = loc.distance((*remain_iter)->position_);
843  if (dist < closest_dist)
844  {
845  closest = remain_iter;
846  closest_dist = dist;
847  }
848  }
849 
850  // no tracker is within a threshold of this candidate
851  // so create a new tracker for this candidate
852  if (closest == propagated.end())
853  std::list<SavedFeature*>::iterator new_saved =
854  saved_features_.insert(saved_features_.end(), new SavedFeature(loc, tfl_));
855  else
856  matches.insert(MatchedFeature(matched_iter->candidate_, *closest, closest_dist, matched_iter->probability_));
857  matches.erase(matched_iter);
858  }
859  }
860 
861  if (!use_seeds_)
862  pairLegs();
863 
864  // Publish Data!
865  int i = 0;
866  std::vector<people_msgs::PositionMeasurement> people;
867  std::vector<people_msgs::PositionMeasurement> legs;
868 
869  for (std::list<SavedFeature*>::iterator sf_iter = saved_features_.begin();
870  sf_iter != saved_features_.end();
871  sf_iter++, i++)
872  {
873  // reliability
874  double reliability = (*sf_iter)->getReliability();
875 
876  if ((*sf_iter)->getReliability() > leg_reliability_limit_
877  && publish_legs_)
878  {
879  people_msgs::PositionMeasurement pos;
880  pos.header.stamp = scan->header.stamp;
881  pos.header.frame_id = fixed_frame;
882  pos.name = "leg_detector";
883  pos.object_id = (*sf_iter)->id_;
884  pos.pos.x = (*sf_iter)->position_[0];
885  pos.pos.y = (*sf_iter)->position_[1];
886  pos.pos.z = (*sf_iter)->position_[2];
887  pos.reliability = reliability;
888  pos.covariance[0] = pow(0.3 / reliability, 2.0);
889  pos.covariance[1] = 0.0;
890  pos.covariance[2] = 0.0;
891  pos.covariance[3] = 0.0;
892  pos.covariance[4] = pow(0.3 / reliability, 2.0);
893  pos.covariance[5] = 0.0;
894  pos.covariance[6] = 0.0;
895  pos.covariance[7] = 0.0;
896  pos.covariance[8] = 10000.0;
897  pos.initialization = 0;
898  legs.push_back(pos);
899  }
900 
901  if (publish_leg_markers_)
902  {
903  visualization_msgs::Marker m;
904  m.header.stamp = (*sf_iter)->time_;
905  m.header.frame_id = fixed_frame;
906  m.ns = "LEGS";
907  m.id = i;
908  m.type = m.SPHERE;
909  m.pose.position.x = (*sf_iter)->position_[0];
910  m.pose.position.y = (*sf_iter)->position_[1];
911  m.pose.position.z = (*sf_iter)->position_[2];
912 
913  m.scale.x = .1;
914  m.scale.y = .1;
915  m.scale.z = .1;
916  m.color.a = 1;
917  m.lifetime = ros::Duration(0.5);
918  if ((*sf_iter)->object_id != "")
919  {
920  m.color.r = 1;
921  }
922  else
923  {
924  m.color.b = (*sf_iter)->getReliability();
925  }
926 
927  markers_pub_.publish(m);
928  }
929 
930  if (publish_people_ || publish_people_markers_)
931  {
932  SavedFeature* other = (*sf_iter)->other;
933  if (other != NULL && other < (*sf_iter))
934  {
935  double dx = ((*sf_iter)->position_[0] + other->position_[0]) / 2,
936  dy = ((*sf_iter)->position_[1] + other->position_[1]) / 2,
937  dz = ((*sf_iter)->position_[2] + other->position_[2]) / 2;
938 
939  if (publish_people_)
940  {
941  reliability = reliability * other->reliability;
942  people_msgs::PositionMeasurement pos;
943  pos.header.stamp = (*sf_iter)->time_;
944  pos.header.frame_id = fixed_frame;
945  pos.name = (*sf_iter)->object_id;;
946  pos.object_id = (*sf_iter)->id_ + "|" + other->id_;
947  pos.pos.x = dx;
948  pos.pos.y = dy;
949  pos.pos.z = dz;
950  pos.reliability = reliability;
951  pos.covariance[0] = pow(0.3 / reliability, 2.0);
952  pos.covariance[1] = 0.0;
953  pos.covariance[2] = 0.0;
954  pos.covariance[3] = 0.0;
955  pos.covariance[4] = pow(0.3 / reliability, 2.0);
956  pos.covariance[5] = 0.0;
957  pos.covariance[6] = 0.0;
958  pos.covariance[7] = 0.0;
959  pos.covariance[8] = 10000.0;
960  pos.initialization = 0;
961  people.push_back(pos);
962  }
963 
964  if (publish_people_markers_)
965  {
966  visualization_msgs::Marker m;
967  m.header.stamp = (*sf_iter)->time_;
968  m.header.frame_id = fixed_frame;
969  m.ns = "PEOPLE";
970  m.id = i;
971  m.type = m.SPHERE;
972  m.pose.position.x = dx;
973  m.pose.position.y = dy;
974  m.pose.position.z = dz;
975  m.scale.x = .2;
976  m.scale.y = .2;
977  m.scale.z = .2;
978  m.color.a = 1;
979  m.color.g = 1;
980  m.lifetime = ros::Duration(0.5);
981 
982  markers_pub_.publish(m);
983  }
984  }
985  }
986  }
987 
988  people_msgs::PositionMeasurementArray array;
989  array.header.stamp = ros::Time::now();
990  if (publish_legs_)
991  {
992  array.people = legs;
993  leg_measurements_pub_.publish(array);
994  }
995  if (publish_people_)
996  {
997  array.people = people;
998  people_measurements_pub_.publish(array);
999  }
1000  }
1001 };
1002 
1003 int main(int argc, char **argv)
1004 {
1005  ros::init(argc, argv, "leg_detector");
1006  g_argc = argc;
1007  g_argv = argv;
1008  ros::NodeHandle nh;
1009  LegDetector ld(nh);
1010  ros::spin();
1011 
1012  return 0;
1013 }
virtual void getEstimate(BFL::StatePosVel &est) const
d
static double max_second_leg_age_s
int min_points_per_group
f
double leg_reliability_limit_
double distance(std::list< SavedFeature * >::iterator it1, std::list< SavedFeature * >::iterator it2)
void publish(const boost::shared_ptr< M > &message) const
void laserCallback(const sensor_msgs::LaserScan::ConstPtr &scan)
std::string object_id
ros::Publisher leg_measurements_pub_
cv::Ptr< cv::ml::RTrees > forest
void configure(leg_detector::LegDetectorConfig &config, uint32_t level)
ros::NodeHandle nh_
virtual double getLifetime() const
char ** g_argv
MatchedFeature(laser_processor::SampleSet *candidate, SavedFeature *closest, float distance, double probability)
void update(tf::Stamped< tf::Point > loc, double probability)
dynamic_reconfigure::Server< leg_detector::LegDetectorConfig > server_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool publish_people_markers_
tf::TransformListener & tfl_
int g_argc
message_filters::Subscriber< sensor_msgs::LaserScan > laser_sub_
bool setTransform(const StampedTransform &transform, const std::string &authority="default_authority")
BFL::StatePosVel sys_sigma_
void transformPoint(const std::string &target_frame, const geometry_msgs::PointStamped &stamped_in, geometry_msgs::PointStamped &stamped_out) const
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
static double kal_q
float connected_thresh_
#define ROS_WARN(...)
message_filters::Subscriber< people_msgs::PositionMeasurement > people_sub_
std::vector< float > calcLegFeatures(laser_processor::SampleSet *cluster, const sensor_msgs::LaserScan &scan)
std::string id_
static std::string fixed_frame
ROSCPP_DECL void spin(Spinner &spinner)
tf::MessageFilter< sensor_msgs::LaserScan > laser_notifier_
ros::Publisher people_measurements_pub_
static double max_track_jump_m
static double kal_p
tf::TransformListener tfl_
boost::mutex saved_mutex_
int main(int argc, char **argv)
estimation::TrackerKalman filter_
Duration & fromSec(double t)
SavedFeature * other
bool param(const std::string &param_name, T &param_val, const T &default_val) const
TFSIMD_FORCE_INLINE Vector3()
static double max_meas_jump_m
double getReliability()
SavedFeature(tf::Stamped< tf::Point > loc, tf::TransformListener &tfl)
An ordered set of Samples.
void propagate(ros::Time time)
tf::Stamped< tf::Point > position_
std::list< SavedFeature * > saved_features_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
double getLifetime()
virtual void initialize(const BFL::StatePosVel &mu, const BFL::StatePosVel &sigma, const double time)
static double leg_pair_separation_m
ros::Time meas_time_
tf::MessageFilter< people_msgs::PositionMeasurement > people_notifier_
std::list< SampleSet * > & getClusters()
double reliability
INLINE Rall1d< T, V, S > pow(const Rall1d< T, V, S > &arg, double m)
void peopleCallback(const people_msgs::PositionMeasurement::ConstPtr &people_meas)
ros::Time stamp_
std::string frame_id_
tf::Vector3 vel_
LegDetector(ros::NodeHandle nh)
void updatePosition()
ros::Time time_
laser_processor::SampleSet * candidate_
ros::Publisher markers_pub_
static int nextid
float dist_to_person_
static Time now()
tf::Vector3 pos_
ROSCPP_DECL void shutdown()
void setTargetFrame(const std::string &target_frame)
SavedFeature * closest_
virtual bool updateCorrection(const tf::Vector3 &meas, const MatrixWrapper::SymmetricMatrix &cov)
laser_processor::ScanMask mask_
static double kal_r
static bool use_filter
A mask for filtering out Samples based on range.
void setTolerance(const ros::Duration &tolerance)
static double no_observation_timeout_s
virtual bool updatePrediction(const double time)
TFSIMD_FORCE_INLINE tfScalar length() const
Connection registerCallback(const C &callback)


leg_detector
Author(s): Caroline Pantofaru
autogenerated on Sun Feb 21 2021 03:56:50