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


leg_detector
Author(s): Caroline Pantofaru
autogenerated on Wed Mar 2 2022 00:45:14