36 #include <leg_detector/LegDetectorConfig.h>
40 #include <opencv2/core/core_c.h>
41 #include <opencv2/ml.hpp>
43 #include <people_msgs/PositionMeasurement.h>
44 #include <people_msgs/PositionMeasurementArray.h>
45 #include <sensor_msgs/LaserScan.h>
54 #include <visualization_msgs/Marker.h>
55 #include <dynamic_reconfigure/server.h>
102 snprintf(
id,
sizeof(
id),
"legtrack%d",
nextid++);
103 id_ = std::string(
id);
121 BFL::StatePosVel prior_sigma(tf::Vector3(0.1, 0.1, 0.1), tf::Vector3(0.0000001, 0.0000001, 0.0000001));
147 MatrixWrapper::SymmetricMatrix cov(3);
192 double nreliability = fmin(1.0, fmax(0.1, est.
vel_.length() / 0.5));
265 dynamic_reconfigure::Server<leg_detector::LegDetectorConfig>
server_;
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);
292 printf(
"Please provide a trained random forests classifier as an input.\n");
311 dynamic_reconfigure::Server<leg_detector::LegDetectorConfig>::CallbackType
f;
323 void configure(leg_detector::LegDetectorConfig &config, uint32_t level)
338 if (std::string(
fixed_frame).compare(config.fixed_frame) != 0)
345 kal_p = config.kalman_p;
346 kal_q = config.kalman_q;
347 kal_r = config.kalman_r;
351 double distance(std::list<SavedFeature*>::iterator it1, std::list<SavedFeature*>::iterator it2)
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);
361 void peopleCallback(
const people_msgs::PositionMeasurement::ConstPtr& people_meas)
368 pointMsgToTF(people_meas->pos, pt);
385 std::list<SavedFeature*>::iterator it1, it2;
397 for (it1 = begin; it1 != end; ++it1)
409 (*it1)->dist_to_person_ = dest_loc.length();
413 std::cout <<
"Looking for two legs" << std::endl;
415 for (it1 = begin; it1 != end; ++it1)
418 if ((*it1)->object_id == people_meas->object_id)
433 (*it1)->object_id =
"";
438 if (it1 != end && it2 != end)
440 std::cout <<
"Found matching pair. The second distance was " << (*it1)->dist_to_person_ << std::endl;
450 std::cout <<
"Looking for one leg plus one new leg" << std::endl;
451 float dist_between_legs, closest_dist_between_legs;
457 for (it1 = begin; it1 != end; ++it1)
464 if ((it1 == it2) || ((*it1)->object_id !=
"") || ((*it1)->getLifetime() >
max_second_leg_age_s) ||
465 ((*it1)->dist_to_person_ >= closest_dist))
475 ROS_WARN(
"TF exception getting distance between legs.");
477 dist_between_legs = dest_loc.length();
483 closest_dist = (*it1)->dist_to_person_;
484 closest_dist_between_legs = dist_between_legs;
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;
496 std::cout <<
"Returned one matched leg only" << std::endl;
503 std::cout <<
"Looking for a pair of new legs" << std::endl;
513 for (; it1 != end; ++it1)
516 if ((*it1)->object_id !=
"" || (*it1)->dist_to_person_ >=
max_meas_jump_m)
520 if ((*it1)->dist_to_person_ < closest_dist)
522 closest_dist = (*it1)->dist_to_person_;
529 for (; it2 != end; ++it2)
532 if ((*it2)->object_id !=
"" || (*it2)->dist_to_person_ >=
max_meas_jump_m)
542 ROS_WARN(
"TF exception getting distance between legs in spot 2.");
544 dist_between_legs = dest_loc.length();
548 if ((*it1)->dist_to_person_ + (*it2)->dist_to_person_ < closest_pair_dist &&
551 closest_pair_dist = (*it1)->dist_to_person_ + (*it2)->dist_to_person_;
554 closest_dist_between_legs = dist_between_legs;
559 if (closest1 != end && closest2 != end)
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;
568 std::cout <<
"Looking for just one leg" << std::endl;
572 (*closest)->object_id = people_meas->object_id;
573 std::cout <<
"Returned one new leg only" << std::endl;
577 std::cout <<
"Nothing matched" << std::endl;
585 std::list<SavedFeature*>::iterator leg1, leg2, best, it;
587 for (leg1 = begin; leg1 != end; ++leg1)
590 if ((*leg1)->object_id ==
"")
596 for (it = begin; it != end; ++it)
598 if (it == leg1)
continue;
600 if ((*it)->object_id == (*leg1)->object_id)
606 if ((*it)->object_id !=
"")
611 && (
d < closest_dist))
620 double dist_between_legs =
distance(leg1, leg2);
623 (*leg1)->object_id =
"";
624 (*leg1)->other = NULL;
625 (*leg2)->object_id =
"";
626 (*leg2)->other = NULL;
630 (*leg1)->other = *leg2;
631 (*leg2)->other = *leg1;
634 else if (best != end)
636 (*best)->object_id = (*leg1)->object_id;
637 (*leg1)->other = *best;
638 (*best)->other = *leg1;
645 std::list<SavedFeature*>::iterator best1 = end, best2 = end;
648 for (leg1 = begin; leg1 != end; ++leg1)
651 if ((*leg1)->object_id !=
""
655 for (leg2 = begin; leg2 != end; ++leg2)
657 if (((*leg2)->object_id !=
"")
659 || (leg1 == leg2))
continue;
661 if (
d < closest_dist)
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;
692 cv::Mat tmp_mat = cv::Mat(1,
feat_count_, CV_32FC1);
699 if ((*sf_iter)->meas_time_ < purge)
701 if ((*sf_iter)->other)
702 (*sf_iter)->other->other = NULL;
712 std::list<SavedFeature*> propagated;
713 for (std::list<SavedFeature*>::iterator sf_iter =
saved_features_.begin();
717 (*sf_iter)->propagate(scan->header.stamp);
718 propagated.push_back(*sf_iter);
725 std::multiset<MatchedFeature> matches;
726 for (std::list<laser_processor::SampleSet*>::iterator i = processor.
getClusters().begin();
732 memcpy(tmp_mat.data,
f.data(),
f.size()*
sizeof(
float));
734 float probability = 0.5 -
735 forest->predict(tmp_mat, cv::noArray(), cv::ml::RTrees::PREDICT_SUM) /
736 forest->getRoots().size();
748 std::list<SavedFeature*>::iterator closest = propagated.end();
751 for (std::list<SavedFeature*>::iterator pf_iter = propagated.begin();
752 pf_iter != propagated.end();
756 float dist = loc.distance((*pf_iter)->position_);
757 if (dist < closest_dist)
764 if (closest == propagated.end())
766 std::list<SavedFeature*>::iterator new_saved =
771 matches.insert(
MatchedFeature(*i, *closest, closest_dist, probability));
776 while (matches.size() > 0)
778 std::multiset<MatchedFeature>::iterator matched_iter = matches.begin();
780 std::list<SavedFeature*>::iterator pf_iter = propagated.begin();
781 while (pf_iter != propagated.end())
784 if (matched_iter->closest_ == *pf_iter)
787 tf::Stamped<tf::Point> loc(matched_iter->candidate_->center(), scan->header.stamp, scan->header.frame_id);
798 matched_iter->closest_->update(loc, matched_iter->probability_);
801 matches.erase(matched_iter);
802 propagated.erase(pf_iter++);
817 tf::Stamped<tf::Point> loc(matched_iter->candidate_->center(), scan->header.stamp, scan->header.frame_id);
827 std::list<SavedFeature*>::iterator closest = propagated.end();
830 for (std::list<SavedFeature*>::iterator remain_iter = propagated.begin();
831 remain_iter != propagated.end();
834 float dist = loc.distance((*remain_iter)->position_);
835 if (dist < closest_dist)
837 closest = remain_iter;
844 if (closest == propagated.end())
845 std::list<SavedFeature*>::iterator new_saved =
848 matches.insert(
MatchedFeature(matched_iter->candidate_, *closest, closest_dist, matched_iter->probability_));
849 matches.erase(matched_iter);
858 std::vector<people_msgs::PositionMeasurement> people;
859 std::vector<people_msgs::PositionMeasurement> legs;
861 for (std::list<SavedFeature*>::iterator sf_iter =
saved_features_.begin();
866 double reliability = (*sf_iter)->getReliability();
871 people_msgs::PositionMeasurement pos;
872 pos.header.stamp = scan->header.stamp;
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;
895 visualization_msgs::Marker m;
896 m.header.stamp = (*sf_iter)->time_;
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];
910 if ((*sf_iter)->object_id !=
"")
916 m.color.b = (*sf_iter)->getReliability();
925 if (other != NULL && other < (*sf_iter))
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;
934 people_msgs::PositionMeasurement pos;
935 pos.header.stamp = (*sf_iter)->time_;
937 pos.name = (*sf_iter)->object_id;;
938 pos.object_id = (*sf_iter)->id_ +
"|" + other->
id_;
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);
958 visualization_msgs::Marker m;
959 m.header.stamp = (*sf_iter)->time_;
964 m.pose.position.x = dx;
965 m.pose.position.y = dy;
966 m.pose.position.z = dz;
980 people_msgs::PositionMeasurementArray array;
989 array.people = people;
995 int main(
int argc,
char **argv)