36 #include <leg_detector/LegDetectorConfig.h> 40 #include <opencv/cxcore.h> 41 #include <opencv/cv.h> 42 #include <opencv/ml.h> 44 #include <people_msgs/PositionMeasurement.h> 45 #include <people_msgs/PositionMeasurementArray.h> 46 #include <sensor_msgs/LaserScan.h> 55 #include <visualization_msgs/Marker.h> 56 #include <dynamic_reconfigure/server.h> 99 filter_(
"tracker_name", sys_sigma_),
100 reliability(-1.), p(4)
103 snprintf(
id,
sizeof(
id),
"legtrack%d", nextid++);
104 id_ = std::string(
id);
148 MatrixWrapper::SymmetricMatrix cov(3);
160 reliability = probability;
166 double k = p / (p +
kal_r);
188 position_[0] = est.
pos_[0];
189 position_[1] = est.
pos_[1];
190 position_[2] = est.
pos_[2];
193 double nreliability = fmin(1.0, fmax(0.1, est.
vel_.
length() / 0.5));
212 : candidate_(candidate)
214 , distance_(distance)
215 , probability_(probability)
266 dynamic_reconfigure::Server<leg_detector::LegDetectorConfig>
server_;
278 people_sub_(nh_,
"people_tracker_filter", 10),
279 laser_sub_(nh_,
"scan", 10),
280 people_notifier_(people_sub_, tfl_,
fixed_frame, 10),
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]);
293 printf(
"Please provide a trained random forests classifier as an input.\n");
297 nh_.
param<
bool>(
"use_seeds", use_seeds_, !
true);
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);
312 dynamic_reconfigure::Server<leg_detector::LegDetectorConfig>::CallbackType
f;
314 server_.setCallback(f);
324 void configure(leg_detector::LegDetectorConfig &config, uint32_t level)
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;
346 kal_p = config.kalman_p;
347 kal_q = config.kalman_q;
348 kal_r = config.kalman_r;
352 double distance(std::list<SavedFeature*>::iterator it1, std::list<SavedFeature*>::iterator it2)
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);
362 void peopleCallback(
const people_msgs::PositionMeasurement::ConstPtr& people_meas)
365 if (saved_features_.empty())
369 pointMsgToTF(people_meas->pos, pt);
376 boost::mutex::scoped_lock lock(saved_mutex_);
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();
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;
398 for (it1 = begin; it1 != end; ++it1)
410 (*it1)->dist_to_person_ = dest_loc.length();
414 std::cout <<
"Looking for two legs" << std::endl;
416 for (it1 = begin; it1 != end; ++it1)
419 if ((*it1)->object_id == people_meas->object_id)
434 (*it1)->object_id =
"";
439 if (it1 != end && it2 != end)
441 std::cout <<
"Found matching pair. The second distance was " << (*it1)->dist_to_person_ << std::endl;
451 std::cout <<
"Looking for one leg plus one new leg" << std::endl;
452 float dist_between_legs, closest_dist_between_legs;
456 closest = saved_features_.end();
458 for (it1 = begin; it1 != end; ++it1)
465 if ((it1 == it2) || ((*it1)->object_id !=
"") || ((*it1)->getLifetime() >
max_second_leg_age_s) ||
466 ((*it1)->dist_to_person_ >= closest_dist))
476 ROS_WARN(
"TF exception getting distance between legs.");
478 dist_between_legs = dest_loc.length();
484 closest_dist = (*it1)->dist_to_person_;
485 closest_dist_between_legs = dist_between_legs;
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;
497 std::cout <<
"Returned one matched leg only" << std::endl;
504 std::cout <<
"Looking for a pair of new legs" << std::endl;
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();
514 for (; it1 != end; ++it1)
517 if ((*it1)->object_id !=
"" || (*it1)->dist_to_person_ >=
max_meas_jump_m)
521 if ((*it1)->dist_to_person_ < closest_dist)
523 closest_dist = (*it1)->dist_to_person_;
530 for (; it2 != end; ++it2)
533 if ((*it2)->object_id !=
"" || (*it2)->dist_to_person_ >=
max_meas_jump_m)
543 ROS_WARN(
"TF exception getting distance between legs in spot 2.");
545 dist_between_legs = dest_loc.length();
549 if ((*it1)->dist_to_person_ + (*it2)->dist_to_person_ < closest_pair_dist &&
552 closest_pair_dist = (*it1)->dist_to_person_ + (*it2)->dist_to_person_;
555 closest_dist_between_legs = dist_between_legs;
560 if (closest1 != end && closest2 != end)
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;
569 std::cout <<
"Looking for just one leg" << std::endl;
573 (*closest)->object_id = people_meas->object_id;
574 std::cout <<
"Returned one new leg only" << std::endl;
578 std::cout <<
"Nothing matched" << std::endl;
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;
588 for (leg1 = begin; leg1 != end; ++leg1)
591 if ((*leg1)->object_id ==
"")
597 for (it = begin; it != end; ++it)
599 if (it == leg1)
continue;
601 if ((*it)->object_id == (*leg1)->object_id)
607 if ((*it)->object_id !=
"")
612 && (d < closest_dist))
621 double dist_between_legs =
distance(leg1, leg2);
624 (*leg1)->object_id =
"";
625 (*leg1)->other = NULL;
626 (*leg2)->object_id =
"";
627 (*leg2)->other = NULL;
631 (*leg1)->other = *leg2;
632 (*leg2)->other = *leg1;
635 else if (best != end)
637 (*best)->object_id = (*leg1)->object_id;
638 (*leg1)->other = *best;
639 (*best)->other = *leg1;
646 std::list<SavedFeature*>::iterator best1 = end, best2 = end;
649 for (leg1 = begin; leg1 != end; ++leg1)
652 if ((*leg1)->object_id !=
"" 653 || (*leg1)->getReliability() < leg_reliability_limit_)
656 for (leg2 = begin; leg2 != end; ++leg2)
658 if (((*leg2)->object_id !=
"")
659 || ((*leg2)->getReliability() < leg_reliability_limit_)
660 || (leg1 == leg2))
continue;
662 if (d < closest_dist)
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;
693 cv::Mat tmp_mat = cv::Mat(1, feat_count_, CV_32FC1);
697 std::list<SavedFeature*>::iterator sf_iter = saved_features_.begin();
698 while (sf_iter != saved_features_.end())
700 if ((*sf_iter)->meas_time_ < purge)
702 if ((*sf_iter)->other)
703 (*sf_iter)->other->other = NULL;
705 saved_features_.erase(sf_iter++);
713 std::list<SavedFeature*> propagated;
714 for (std::list<SavedFeature*>::iterator sf_iter = saved_features_.begin();
715 sf_iter != saved_features_.end();
718 (*sf_iter)->propagate(scan->header.stamp);
719 propagated.push_back(*sf_iter);
726 std::multiset<MatchedFeature> matches;
727 for (std::list<laser_processor::SampleSet*>::iterator i = processor.
getClusters().begin();
733 memcpy(tmp_mat.data, f.data(), f.size()*
sizeof(float));
741 forest->getVotes(tmp_mat, votes, 0);
744 float probability =
static_cast<float>(votes.at<
int>(1, 1)) /
static_cast<float>(forest->getRoots().size());
756 std::list<SavedFeature*>::iterator closest = propagated.end();
759 for (std::list<SavedFeature*>::iterator pf_iter = propagated.begin();
760 pf_iter != propagated.end();
764 float dist = loc.distance((*pf_iter)->position_);
765 if (dist < closest_dist)
772 if (closest == propagated.end())
774 std::list<SavedFeature*>::iterator new_saved =
775 saved_features_.insert(saved_features_.end(),
new SavedFeature(loc, tfl_));
779 matches.insert(
MatchedFeature(*i, *closest, closest_dist, probability));
784 while (matches.size() > 0)
786 std::multiset<MatchedFeature>::iterator matched_iter = matches.begin();
788 std::list<SavedFeature*>::iterator pf_iter = propagated.begin();
789 while (pf_iter != propagated.end())
792 if (matched_iter->closest_ == *pf_iter)
795 tf::Stamped<tf::Point> loc(matched_iter->candidate_->center(), scan->header.stamp, scan->header.frame_id);
806 matched_iter->closest_->update(loc, matched_iter->probability_);
809 matches.erase(matched_iter);
810 propagated.erase(pf_iter++);
825 tf::Stamped<tf::Point> loc(matched_iter->candidate_->center(), scan->header.stamp, scan->header.frame_id);
835 std::list<SavedFeature*>::iterator closest = propagated.end();
838 for (std::list<SavedFeature*>::iterator remain_iter = propagated.begin();
839 remain_iter != propagated.end();
842 float dist = loc.distance((*remain_iter)->position_);
843 if (dist < closest_dist)
845 closest = remain_iter;
852 if (closest == propagated.end())
853 std::list<SavedFeature*>::iterator new_saved =
854 saved_features_.insert(saved_features_.end(),
new SavedFeature(loc, tfl_));
856 matches.insert(
MatchedFeature(matched_iter->candidate_, *closest, closest_dist, matched_iter->probability_));
857 matches.erase(matched_iter);
866 std::vector<people_msgs::PositionMeasurement> people;
867 std::vector<people_msgs::PositionMeasurement> legs;
869 for (std::list<SavedFeature*>::iterator sf_iter = saved_features_.begin();
870 sf_iter != saved_features_.end();
876 if ((*sf_iter)->getReliability() > leg_reliability_limit_
879 people_msgs::PositionMeasurement pos;
880 pos.header.stamp = scan->header.stamp;
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];
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;
901 if (publish_leg_markers_)
903 visualization_msgs::Marker m;
904 m.header.stamp = (*sf_iter)->time_;
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];
918 if ((*sf_iter)->object_id !=
"")
924 m.color.b = (*sf_iter)->getReliability();
930 if (publish_people_ || publish_people_markers_)
933 if (other != NULL && other < (*sf_iter))
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;
942 people_msgs::PositionMeasurement pos;
943 pos.header.stamp = (*sf_iter)->time_;
945 pos.name = (*sf_iter)->object_id;;
946 pos.object_id = (*sf_iter)->id_ +
"|" + other->
id_;
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);
964 if (publish_people_markers_)
966 visualization_msgs::Marker m;
967 m.header.stamp = (*sf_iter)->time_;
972 m.pose.position.x = dx;
973 m.pose.position.y = dy;
974 m.pose.position.z = dz;
988 people_msgs::PositionMeasurementArray array;
993 leg_measurements_pub_.
publish(array);
997 array.people = people;
998 people_measurements_pub_.
publish(array);
virtual void getEstimate(BFL::StatePosVel &est) const
static double max_second_leg_age_s
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)
ros::Publisher leg_measurements_pub_
cv::Ptr< cv::ml::RTrees > forest
void configure(leg_detector::LegDetectorConfig &config, uint32_t level)
virtual double getLifetime() const
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_
message_filters::Subscriber< sensor_msgs::LaserScan > laser_sub_
BFL::StatePosVel sys_sigma_
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
message_filters::Subscriber< people_msgs::PositionMeasurement > people_sub_
std::vector< float > calcLegFeatures(laser_processor::SampleSet *cluster, const sensor_msgs::LaserScan &scan)
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
tf::TransformListener tfl_
boost::mutex saved_mutex_
int main(int argc, char **argv)
estimation::TrackerKalman filter_
void splitConnected(float thresh)
Duration & fromSec(double t)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
TFSIMD_FORCE_INLINE Vector3()
static double max_meas_jump_m
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)
virtual void initialize(const BFL::StatePosVel &mu, const BFL::StatePosVel &sigma, const double time)
static double leg_pair_separation_m
tf::MessageFilter< people_msgs::PositionMeasurement > people_notifier_
std::list< SampleSet * > & getClusters()
INLINE Rall1d< T, V, S > pow(const Rall1d< T, V, S > &arg, double m)
void peopleCallback(const people_msgs::PositionMeasurement::ConstPtr &people_meas)
LegDetector(ros::NodeHandle nh)
laser_processor::SampleSet * candidate_
ros::Publisher markers_pub_
ROSCPP_DECL void shutdown()
void setTargetFrame(const std::string &target_frame)
void removeLessThan(uint32_t num)
virtual bool updateCorrection(const tf::Vector3 &meas, const MatrixWrapper::SymmetricMatrix &cov)
laser_processor::ScanMask mask_
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)