00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056
00057
00058
00059
00060
00061
00062
00063
00064
00065
00066
00067
00068
00069
00070
00071
00072
00073
00074
00075
00076
00077
00078
00079
00080
00081
00082
00083
00084
00085
00086
00087
00088
00089
00090
00091
00092
00093
00094
00095
00096
00097
00098
00099 #include <ros/ros.h>
00100
00101 #include <cob_leg_detection/LegDetectionConfig.h>
00102 #include <cob_leg_detection/laser_processor.h>
00103 #include <cob_leg_detection/calc_leg_features.h>
00104
00105 #include <opencv2/opencv.hpp>
00106
00107 #include <cob_perception_msgs/PositionMeasurement.h>
00108 #include <cob_perception_msgs/PositionMeasurementArray.h>
00109 #include <cob_perception_msgs/Person.h>
00110 #include <cob_perception_msgs/People.h>
00111 #include <sensor_msgs/LaserScan.h>
00112
00113 #include <tf/transform_listener.h>
00114 #include <tf/message_filter.h>
00115 #include <message_filters/subscriber.h>
00116
00117 #include <cob_people_tracking_filter/tracker_kalman.h>
00118 #include <cob_people_tracking_filter/state_pos_vel.h>
00119 #include <cob_people_tracking_filter/rgb.h>
00120 #include <visualization_msgs/Marker.h>
00121 #include <dynamic_reconfigure/server.h>
00122
00123 #include <tf/transform_broadcaster.h>
00124 #include <tf/transform_listener.h>
00125
00126 #include <algorithm>
00127 #include <vector>
00128
00129 using namespace std;
00130 using namespace laser_processor;
00131 using namespace ros;
00132 using namespace tf;
00133 using namespace estimation;
00134 using namespace BFL;
00135 using namespace MatrixWrapper;
00136
00137
00138 static double no_observation_timeout_s = 0.5;
00139 static double max_second_leg_age_s = 2.0 ;
00140 static double max_track_jump_m = 1.0;
00141 static double max_meas_jump_m = 0.75;
00142 static double leg_pair_separation_m = 0.50;
00143 static string fixed_frame = "base_link";
00144 static double cov_meas_legs_m = 0.025;
00145 static double cov_meas_people_m = 0.025;
00146
00147 static double kal_p = 4, kal_q = .002, kal_r = 10;
00148 static bool use_filter = true;
00149
00150 static string detector_ = "laser_scaner";
00151
00152
00153
00154
00155
00156
00157
00158
00159
00160
00161
00162
00163
00164
00165
00166
00167
00168
00169
00170
00171
00172
00173
00174
00175 class SavedPersonFeature
00176 {
00177 public:
00178
00179 string id_;
00180 string object_id;
00181 string person_name;
00182
00183 Stamped<Point> position_;
00184 Stamped<Vector3> velocity_;
00185
00186
00187
00188 BFL::StatePosVel sys_sigma_;
00189 TrackerKalman filter_;
00190 ros::Time time_;
00191 ros::Time meas_time_;
00192
00193 double reliability, p, probability;
00194
00195
00196 SavedPersonFeature(Stamped<Point> loc, std::string& id, std::string& name)
00197 : sys_sigma_(Vector3(0.05, 0.05, 0.05), Vector3(1.0, 1.0, 1.0)),
00198 filter_("tracker_people",sys_sigma_),
00199 reliability(-1.), p(4)
00200 {
00201 object_id = id;
00202 person_name = name;
00203 time_ = loc.stamp_;
00204
00205
00206
00207
00208
00209
00210
00211 StatePosVel prior_sigma(Vector3(0.1,0.1,0.1), Vector3(0.0000001, 0.0000001, 0.0000001));
00212 filter_.initialize(loc, prior_sigma, time_.toSec());
00213 StatePosVel est;
00214 filter_.getEstimate(est);
00215 updatePosition();
00216 }
00217
00218
00219
00220
00221 void propagate(ros::Time time)
00222 {
00223 time_ = time;
00224 filter_.updatePrediction(time.toSec());
00225 updatePosition();
00226 }
00227
00228
00229
00230
00231
00232
00233 void update(Stamped<Point> loc, double probability)
00234 {
00235
00236
00237 meas_time_ = loc.stamp_;
00238 time_ = meas_time_;
00239
00240
00241 SymmetricMatrix cov(3);
00242 cov = 0.0;
00243 cov(1,1) = cov_meas_people_m;
00244 cov(2,2) = cov_meas_people_m;
00245 cov(3,3) = cov_meas_people_m;
00246
00247 filter_.updateCorrection(loc, cov);
00248 updatePosition();
00249
00250 }
00251
00252
00253
00254
00255 double getLifetime()
00256 {
00257 return filter_.getLifetime();
00258 }
00259
00260 double getReliability()
00261 {
00262 return reliability;
00263 }
00264
00265 private:
00266
00267
00268
00269
00270 void updatePosition()
00271 {
00272 StatePosVel est;
00273 filter_.getEstimate(est);
00274
00275 position_[0] = est.pos_[0];
00276 position_[1] = est.pos_[1];
00277 position_[2] = est.pos_[2];
00278
00279 velocity_[0] = est.vel_[0];
00280 velocity_[1] = est.vel_[1];
00281 velocity_[2] = est.vel_[2];
00282
00283 position_.stamp_ = time_;
00284 position_.frame_id_ = fixed_frame;
00285 velocity_.stamp_ = time_;
00286 velocity_.frame_id_ = fixed_frame;
00287 }
00288 };
00289
00290 class SavedFeature
00291 {
00292 public:
00293 static int nextid;
00294 TransformListener& tfl_;
00295
00296 BFL::StatePosVel sys_sigma_;
00297 TrackerKalman filter_;
00298
00299 string id_;
00300 string object_id;
00301 ros::Time time_;
00302 ros::Time meas_time_;
00303
00304 double reliability, p, probability;
00305
00306 Stamped<Point> position_;
00307 Stamped<Vector3> velocity_;
00308 SavedFeature* other;
00309 float dist_to_person_;
00310
00311
00312
00313 SavedFeature(Stamped<Point> loc, TransformListener& tfl)
00314 : tfl_(tfl),
00315 sys_sigma_(Vector3(0.05, 0.05, 0.05), Vector3(1.0, 1.0, 1.0)),
00316 filter_("tracker_legs",sys_sigma_),
00317 reliability(-1.), p(4)
00318 {
00319 char id[100];
00320 snprintf(id,100,"legtrack %d", nextid++);
00321 id_ = std::string(id);
00322
00323 object_id = "";
00324 time_ = loc.stamp_;
00325 meas_time_ = loc.stamp_;
00326 other = NULL;
00327
00328 try {
00329 tfl_.transformPoint(fixed_frame, loc, loc);
00330 } catch(...) {
00331 ROS_WARN("TF exception spot 6.");
00332 }
00333 StampedTransform pose( Pose(Quaternion(0.0, 0.0, 0.0, 1.0), loc), loc.stamp_, id_, loc.frame_id_);
00334 tfl_.setTransform(pose);
00335
00336 StatePosVel prior_sigma(Vector3(0.1,0.1,0.1), Vector3(0.0000001, 0.0000001, 0.0000001));
00337 filter_.initialize(loc, prior_sigma, time_.toSec());
00338 StatePosVel est;
00339 filter_.getEstimate(est);
00340 updatePosition();
00341
00342 }
00343
00344 void propagate(ros::Time time)
00345 {
00346 time_ = time;
00347 filter_.updatePrediction(time.toSec());
00348 updatePosition();
00349 }
00350
00351 void update(Stamped<Point> loc, double probability)
00352 {
00353 StampedTransform pose( Pose(Quaternion(0.0, 0.0, 0.0, 1.0), loc), loc.stamp_, id_, loc.frame_id_);
00354 tfl_.setTransform(pose);
00355
00356 meas_time_ = loc.stamp_;
00357 time_ = meas_time_;
00358
00359 SymmetricMatrix cov(3);
00360 cov = 0.0;
00361 cov(1,1) = cov_meas_legs_m;
00362 cov(2,2) = cov_meas_legs_m;
00363 cov(3,3) = cov_meas_legs_m;
00364
00365 filter_.updateCorrection(loc, cov);
00366 updatePosition();
00367
00368 if(reliability<0 || !use_filter){
00369 reliability = probability;
00370 p = kal_p;
00371 }
00372 else{
00373 p += kal_q;
00374 double k = p / (p+kal_r);
00375 reliability += k * (probability - reliability);
00376 p *= (1 - k);
00377 }
00378 }
00379
00380 double getLifetime()
00381 {
00382 return filter_.getLifetime();
00383 }
00384
00385 double getReliability()
00386 {
00387 return reliability;
00388 }
00389
00390 private:
00391 void updatePosition()
00392 {
00393 StatePosVel est;
00394 filter_.getEstimate(est);
00395
00396 position_[0] = est.pos_[0];
00397 position_[1] = est.pos_[1];
00398 position_[2] = est.pos_[2];
00399
00400 velocity_[0] = est.vel_[0];
00401 velocity_[1] = est.vel_[1];
00402 velocity_[2] = est.vel_[2];
00403
00404 position_.stamp_ = time_;
00405 position_.frame_id_ = fixed_frame;
00406 velocity_.stamp_ = time_;
00407 velocity_.frame_id_ = fixed_frame;
00408
00409 double nreliability = fmin(1.0, fmax(0.1, est.vel_.length() / 0.5));
00410 }
00411
00412 };
00413
00414 int SavedFeature::nextid = 0;
00415
00416
00417 class MatchedFeature
00418 {
00419 public:
00420 SampleSet* candidate_;
00421 SavedFeature* closest_;
00422 float distance_;
00423 double probability_;
00424
00425 MatchedFeature(SampleSet* candidate, SavedFeature* closest, float distance, double probability)
00426 : candidate_(candidate)
00427 , closest_(closest)
00428 , distance_(distance)
00429 , probability_(probability)
00430 {}
00431
00432 inline bool operator< (const MatchedFeature& b) const
00433 {
00434 return (distance_ < b.distance_);
00435 }
00436 };
00437
00438 int g_argc;
00439 char** g_argv;
00440
00441
00442
00443
00444
00445 class LegDetector
00446 {
00447 public:
00448 NodeHandle nh_;
00449 TransformListener tfl_;
00450
00451 ScanMask mask_;
00452 int mask_count_;
00453 #if CV_MAJOR_VERSION == 2
00454 CvRTrees forest;
00455 #else
00456
00457 cv::Ptr<cv::ml::RTrees> forest;
00458 #endif
00459 float connected_thresh_;
00460 int feat_count_;
00461 char save_[100];
00462 list<SavedFeature*> saved_features_;
00463 boost::mutex saved_mutex_;
00464 int feature_id_;
00465 bool use_seeds_;
00466 bool publish_legs_, publish_people_, publish_leg_markers_, publish_people_markers_, publish_vel_markers_;
00467 int next_p_id_;
00468 double leg_reliability_limit_;
00469 int min_points_per_group;
00470
00471 ros::Publisher people_measurements_pub_;
00472 ros::Publisher leg_measurements_pub_;
00473 ros::Publisher people_pub_;
00474 ros::Publisher markers_pub_;
00475
00476 dynamic_reconfigure::Server<cob_leg_detection::LegDetectionConfig> server_;
00477
00478 message_filters::Subscriber<cob_perception_msgs::PositionMeasurementArray> people_sub_;
00479 message_filters::Subscriber<sensor_msgs::LaserScan> laser_sub_;
00480
00481 tf::MessageFilter<sensor_msgs::LaserScan> laser_notifier_;
00482
00483
00484 list<SavedPersonFeature*>saved_people_;
00485
00486 tf::TransformBroadcaster br_;
00487
00488 LegDetector(ros::NodeHandle nh) :
00489 nh_(nh),
00490 mask_count_(0),
00491 feat_count_(0),
00492 next_p_id_(0),
00493 laser_sub_(nh_,"scan",10),
00494 laser_notifier_(laser_sub_,tfl_,fixed_frame,10)
00495 {
00496
00497 if (g_argc > 1) {
00498 #if CV_MAJOR_VERSION == 2
00499 forest.load(g_argv[1]);
00500 feat_count_ = forest.get_active_var_mask()->cols;
00501 #else
00502
00503 forest = cv::ml::RTrees::create();
00504 cv::String feature_file = cv::String(g_argv[1]);
00505 forest = cv::ml::StatModel::load<cv::ml::RTrees>(feature_file);
00506 feat_count_ = forest->getVarCount();
00507 #endif
00508 printf("Loaded forest with %d features: %s\n", feat_count_, g_argv[1]);
00509 } else {
00510 printf("Please provide a trained random forests classifier as an input.\n");
00511 shutdown();
00512 }
00513
00514
00515 leg_measurements_pub_ = nh_.advertise<cob_perception_msgs::PositionMeasurementArray>("leg_tracker_measurements",0);
00516 people_measurements_pub_ = nh_.advertise<cob_perception_msgs::PositionMeasurementArray>("people_tracker_measurements", 0);
00517
00518 people_pub_ = nh_.advertise<cob_perception_msgs::People>("people",0);
00519 markers_pub_ = nh_.advertise<visualization_msgs::Marker>("visualization_marker", 20);
00520
00521 laser_notifier_.registerCallback(boost::bind(&LegDetector::laserCallback, this, _1));
00522 laser_notifier_.setTolerance(ros::Duration(0.01));
00523
00524 people_sub_.subscribe(nh_,"people_tracker_measurements",10);
00525 people_sub_.registerCallback(boost::bind(&LegDetector::peopleCallback, this, _1));
00526
00527 dynamic_reconfigure::Server<cob_leg_detection::LegDetectionConfig>::CallbackType f;
00528 f = boost::bind(&LegDetector::configure, this, _1, _2);
00529 server_.setCallback(f);
00530
00531 feature_id_ = 0;
00532 }
00533
00534 ~LegDetector()
00535 {
00536 }
00537
00538 void configure(cob_leg_detection::LegDetectionConfig &config, uint32_t level)
00539 {
00540 connected_thresh_ = config.connection_threshold;
00541 min_points_per_group = config.min_points_per_group;
00542 leg_reliability_limit_ = config.leg_reliability_limit;
00543 publish_legs_ = config.publish_legs;
00544 publish_people_ = config.publish_people;
00545 publish_leg_markers_ = config.publish_leg_markers;
00546 publish_vel_markers_ = config.publish_vel_markers;
00547 publish_people_markers_ = config.publish_people_markers;
00548
00549 no_observation_timeout_s = config.no_observation_timeout;
00550 max_second_leg_age_s = config.max_second_leg_age;
00551 max_track_jump_m = config.max_track_jump;
00552 max_meas_jump_m = config.max_meas_jump;
00553 leg_pair_separation_m = config.leg_pair_separation;
00554 cov_meas_legs_m = config.cov_meas_legs;
00555 cov_meas_people_m = config.cov_meas_people;
00556
00557 if(fixed_frame.compare(config.fixed_frame) != 0){
00558 fixed_frame = config.fixed_frame;
00559 laser_notifier_.setTargetFrame(fixed_frame);
00560
00561 }
00562 kal_p = config.kalman_p;
00563 kal_q = config.kalman_q;
00564 kal_r = config.kalman_r;
00565 use_filter = config.kalman_on == 1;
00566 }
00567
00568
00569
00570
00571
00572
00573
00574 void peopleCallback(const cob_perception_msgs::PositionMeasurementArray::ConstPtr& people_meas)
00575 {
00576
00577 if (people_meas->people.empty())
00578 return;
00579
00580 boost::mutex::scoped_lock lock(saved_mutex_);
00581 list<SavedPersonFeature*>::iterator it;
00582 cob_perception_msgs::PositionMeasurement ppl;
00583 list<SavedPersonFeature*> saved_people;
00584
00585
00586 if(saved_people_.size() != 0){
00587
00588
00589 for(list<SavedPersonFeature*>::iterator iter_ = saved_people_.begin();
00590 iter_ != saved_people_.end(); ++iter_){
00591 (*iter_)->propagate(people_meas->header.stamp);
00592 }
00593 }
00594
00595
00596 for(int i = 0; i < people_meas->people.size(); i++){
00597 ppl = people_meas->people.at(i);
00598 Stamped<Point> person_loc(Vector3(ppl.pos.x, ppl.pos.y, ppl.pos.z), people_meas->header.stamp, ppl.header.frame_id);
00599
00600 if(saved_people.size() == 0){
00601 saved_people.insert(saved_people.end(), new SavedPersonFeature(person_loc, ppl.object_id, ppl.name));
00602 }else{
00603 bool found = false;
00604
00605 for (it = saved_people.begin(); it != saved_people.end(); ++it){
00606 if(ppl.name.compare((*it)->person_name) == 0 )
00607 found = true;
00608 }
00609
00610 if(!found){
00611 found = false;
00612 saved_people.insert(saved_people.end(), new SavedPersonFeature(person_loc, ppl.object_id, ppl.name));
00613 }
00614 }
00615 }
00616
00617
00618
00619
00620
00621
00622
00623 if(saved_people_.size() == 0){
00624 for(list<SavedPersonFeature*>::iterator iter = saved_people.begin(); iter != saved_people.end(); ++iter){
00625 saved_people_.push_back((*iter));
00626 }
00627 }else{
00628 for(list<SavedPersonFeature*>::iterator iter = saved_people.begin(); iter != saved_people.end(); ++iter)
00629 {
00630 bool found_temp = false;
00631 for(list<SavedPersonFeature*>::iterator iter_ = saved_people_.begin(); iter_ != saved_people_.end(); ++iter_){
00632 if((*iter)->person_name.compare((*iter_)->person_name) == 0){
00633 found_temp = true;
00634
00635
00636 (*iter_)->update((*iter)->position_, 1.0);
00637 }
00638 }
00639
00640 if(found_temp == false ){
00641 saved_people_.push_back((*iter));
00642 }
00643 }
00644 }
00645
00646
00647 for(list<SavedPersonFeature*>::iterator iter = saved_people_.begin(); iter != saved_people_.end(); ++iter){
00648 bool found_temp = false;
00649 for(list<SavedPersonFeature*>::iterator iter_ = saved_people.begin(); iter_ != saved_people.end(); ++iter_){
00650 if((*iter)->person_name.compare((*iter_)->person_name) == 0){
00651 found_temp = true;
00652 }
00653 }
00654 if(found_temp == false ){
00655 delete (*iter);
00656 saved_people_.erase(iter++);
00657 }
00658 }
00659
00660
00661 PRINT_LIST(saved_people_, "LIST saved_people :: ");
00662
00663
00664 int i = 0;
00665
00666 vector<cob_perception_msgs::Person> people;
00667
00668 for (list<SavedPersonFeature*>::iterator sp_iter = saved_people_.begin();
00669 sp_iter != saved_people_.end(); sp_iter++,i++){
00670
00671 cob_perception_msgs::Person person;
00672 person.detector = detector_;
00673 person.name = (*sp_iter)->person_name;
00674 person.position.position.x = (*sp_iter)->position_[0];
00675 person.position.position.y = (*sp_iter)->position_[1];
00676 person.position.position.z = (*sp_iter)->position_[2];
00677
00678 person.velocity.x = (*sp_iter)->velocity_[0];
00679 person.velocity.y = (*sp_iter)->velocity_[1];
00680 person.velocity.z = (*sp_iter)->velocity_[2];
00681
00682 people.push_back(person);
00683
00684 double dx = (*sp_iter)->velocity_[0], dy = (*sp_iter)->velocity_[1];
00685 visualization_msgs::Marker m;
00686 m.header.stamp = people_meas->header.stamp;
00687 m.header.frame_id = fixed_frame;
00688 m.ns = "SPEED";
00689 m.type = m.ARROW;
00690 m.pose.position.x = (*sp_iter)->position_[0];
00691 m.pose.position.y = (*sp_iter)->position_[1];
00692 m.pose.position.z = (*sp_iter)->position_[2];
00693 m.pose.orientation.x = (*sp_iter)->velocity_[0];
00694 m.pose.orientation.y = (*sp_iter)->velocity_[1];
00695 m.pose.orientation.z = 0.0;
00696 m.scale.x = sqrt(dx*dx+dy*dy);
00697 ROS_INFO("speed %f", m.scale.x);
00698
00699 m.scale.y = .05;
00700 m.scale.z = .05;
00701 m.color.a = 1;
00702 m.color.r = 1;
00703 m.lifetime = ros::Duration(0.5);
00704
00705 markers_pub_.publish(m);
00706 }
00707
00708 cob_perception_msgs::People array;
00709 array.header.stamp = ros::Time::now();
00710 array.people = people;
00711 people_pub_.publish(array);
00712 }
00713
00714
00715
00716
00717 void laserCallback(const sensor_msgs::LaserScan::ConstPtr& scan)
00718 {
00719 ScanProcessor processor(*scan, mask_);
00720 processor.splitConnected(connected_thresh_);
00721 processor.removeLessThan(5);
00722 #if CV_MAJOR_VERSION == 2
00723 CvMat* tmp_mat = cvCreateMat(1,feat_count_,CV_32FC1);
00724 #else
00725
00726 cv::Mat tmp_mat = cv::Mat(1, feat_count_, CV_32FC1);
00727 #endif
00728
00729
00730 ros::Time purge = scan->header.stamp + ros::Duration().fromSec(-no_observation_timeout_s);
00731 list<SavedFeature*>::iterator sf_iter = saved_features_.begin();
00732 while (sf_iter != saved_features_.end()){
00733 if ((*sf_iter)->meas_time_ < purge){
00734 if( (*sf_iter)->other )
00735 (*sf_iter)->other->other = NULL;
00736 delete (*sf_iter);
00737 saved_features_.erase(sf_iter++);
00738 }else
00739 ++sf_iter;
00740 }
00741
00742
00743
00744 list<SavedFeature*> propagated;
00745 for (list<SavedFeature*>::iterator sf_iter = saved_features_.begin();
00746 sf_iter != saved_features_.end();
00747 sf_iter++){
00748 (*sf_iter)->propagate(scan->header.stamp);
00749 propagated.push_back(*sf_iter);
00750 }
00751
00752
00753
00754
00755 multiset<MatchedFeature> matches;
00756 for (list<SampleSet*>::iterator i = processor.getClusters().begin();
00757 i != processor.getClusters().end();i++){
00758 vector<float> f = calcLegFeatures(*i, *scan);
00759
00760 for (int k = 0; k < feat_count_; k++)
00761 #if CV_MAJOR_VERSION == 2
00762 tmp_mat->data.fl[k] = (float)(f[k]);
00763 #else
00764
00765 tmp_mat.data[k] = (float)(f[k]);
00766 #endif
00767
00768 #if CV_MAJOR_VERSION == 2
00769 float probability = forest.predict_prob( tmp_mat );
00770 #else
00771
00772
00773
00774
00775 float probability = 0.5 -
00776 forest->predict(tmp_mat, cv::noArray(), cv::ml::RTrees::PREDICT_SUM) /
00777 forest->getRoots().size();
00778 #endif
00779 Stamped<Point> loc((*i)->center(), scan->header.stamp, scan->header.frame_id);
00780 try {
00781 tfl_.transformPoint(fixed_frame, loc, loc);
00782 } catch(...) {
00783 ROS_WARN("TF exception spot 3.");
00784 }
00785
00786 list<SavedFeature*>::iterator closest = propagated.end();
00787 float closest_dist = max_track_jump_m;
00788
00789 for (list<SavedFeature*>::iterator pf_iter = propagated.begin();
00790 pf_iter != propagated.end();pf_iter++){
00791
00792 float dist = loc.distance((*pf_iter)->position_);
00793 if ( dist < closest_dist ){
00794 closest = pf_iter;
00795 closest_dist = dist;
00796 }
00797 }
00798
00799 if (closest == propagated.end()){
00800 list<SavedFeature*>::iterator new_saved = saved_features_.insert(saved_features_.end(), new SavedFeature(loc, tfl_));
00801 }else
00802 matches.insert(MatchedFeature(*i,*closest,closest_dist,probability));
00803 }
00804
00805
00806
00807 while (matches.size() > 0){
00808 multiset<MatchedFeature>::iterator matched_iter = matches.begin();
00809 bool found = false;
00810 list<SavedFeature*>::iterator pf_iter = propagated.begin();
00811 while (pf_iter != propagated.end()){
00812
00813 if (matched_iter->closest_ == *pf_iter){
00814
00815 Stamped<Point> loc(matched_iter->candidate_->center(), scan->header.stamp, scan->header.frame_id);
00816 try {
00817 tfl_.transformPoint(fixed_frame, loc, loc);
00818 } catch(...) {
00819 ROS_WARN("TF exception spot 4.");
00820 }
00821
00822
00823 matched_iter->closest_->update(loc, matched_iter->probability_);
00824
00825
00826 matches.erase(matched_iter);
00827 propagated.erase(pf_iter++);
00828 found = true;
00829 break;
00830 }else{
00831 pf_iter++;
00832 }
00833 }
00834
00835
00836
00837 if (!found){
00838 Stamped<Point> loc(matched_iter->candidate_->center(), scan->header.stamp, scan->header.frame_id);
00839 try {
00840 tfl_.transformPoint(fixed_frame, loc, loc);
00841 } catch(...) {
00842 ROS_WARN("TF exception spot 5.");
00843 }
00844 list<SavedFeature*>::iterator closest = propagated.end();
00845 float closest_dist = max_track_jump_m;
00846
00847 for (list<SavedFeature*>::iterator remain_iter = propagated.begin();
00848 remain_iter != propagated.end();remain_iter++){
00849 float dist = loc.distance((*remain_iter)->position_);
00850 if ( dist < closest_dist ){
00851 closest = remain_iter;
00852 closest_dist = dist;
00853 }
00854 }
00855
00856
00857
00858 if (closest == propagated.end())
00859 list<SavedFeature*>::iterator new_saved = saved_features_.insert(saved_features_.end(), new SavedFeature(loc, tfl_));
00860 else
00861 matches.insert(MatchedFeature(matched_iter->candidate_,*closest,closest_dist, matched_iter->probability_));
00862 matches.erase(matched_iter);
00863 }
00864 }
00865
00866 #if CV_MAJOR_VERSION == 2
00867 cvReleaseMat(&tmp_mat); tmp_mat = 0;
00868 #endif
00869
00870 pairLegs();
00871
00872
00873
00874 int i = 0;
00875 vector<cob_perception_msgs::PositionMeasurement> people;
00876 vector<cob_perception_msgs::PositionMeasurement> legs;
00877
00878 for (list<SavedFeature*>::iterator sf_iter = saved_features_.begin();
00879 sf_iter != saved_features_.end(); sf_iter++,i++){
00880
00881 double reliability = (*sf_iter)->getReliability();
00882
00883
00884 if ((*sf_iter)->getReliability() > leg_reliability_limit_
00885 && publish_legs_){
00886
00887 cob_perception_msgs::PositionMeasurement pos;
00888 pos.header.stamp = scan->header.stamp;
00889 pos.header.frame_id = fixed_frame;
00890 pos.name = "leg_detection";
00891 pos.object_id = (*sf_iter)->id_;
00892 pos.pos.x = (*sf_iter)->position_[0];
00893 pos.pos.y = (*sf_iter)->position_[1];
00894 pos.pos.z = (*sf_iter)->position_[2];
00895 pos.vel.x = (*sf_iter)->velocity_[0];
00896 pos.vel.y = (*sf_iter)->velocity_[1];
00897 pos.vel.z = (*sf_iter)->velocity_[2];
00898 pos.reliability = reliability;
00899 pos.covariance[0] = pow(0.3 / reliability,2.0);
00900 pos.covariance[1] = 0.0;
00901 pos.covariance[2] = 0.0;
00902 pos.covariance[3] = 0.0;
00903 pos.covariance[4] = pow(0.3 / reliability,2.0);
00904 pos.covariance[5] = 0.0;
00905 pos.covariance[6] = 0.0;
00906 pos.covariance[7] = 0.0;
00907 pos.covariance[8] = 10000.0;
00908 pos.initialization = 0;
00909 legs.push_back(pos);
00910 }
00911
00912 if (publish_leg_markers_){
00913 visualization_msgs::Marker m;
00914 m.header.stamp = (*sf_iter)->time_;
00915 m.header.frame_id = fixed_frame;
00916 m.ns = "LEGS";
00917 m.id = i;
00918 m.type = m.SPHERE;
00919 m.pose.position.x = (*sf_iter)->position_[0];
00920 m.pose.position.y = (*sf_iter)->position_[1];
00921 m.pose.position.z = (*sf_iter)->position_[2];
00922
00923 m.scale.x = .1;
00924 m.scale.y = .1;
00925 m.scale.z = .1;
00926 m.color.a = 1;
00927 m.lifetime = ros::Duration(0.5);
00928 if((*sf_iter)->object_id != ""){
00929 m.color.r = 1;
00930 }else{
00931 m.color.b = (*sf_iter)->getReliability();
00932 }
00933 markers_pub_.publish(m);
00934 }
00935
00936 if (publish_people_ || publish_people_markers_ ){
00937 SavedFeature* other = (*sf_iter)->other;
00938 if(other!=NULL && other<(*sf_iter)){
00939
00940 Stamped<Point> one = (*sf_iter)->position_, two = (other)->position_;
00941 double ddx = one[0]-two[0], ddy = one[1]-two[1], ddz = one[2]-two[2];
00942 double d = sqrt(ddx*ddx + ddy*ddy + ddz*ddz);
00943
00944
00945 double dx = ((*sf_iter)->position_[0] + other->position_[0])/2,
00946 dy = ((*sf_iter)->position_[1] + other->position_[1])/2,
00947 dz = ((*sf_iter)->position_[2] + other->position_[2])/2;
00948
00949 double vx = ((*sf_iter)->velocity_[0]- ((*sf_iter)->velocity_[0] - other->velocity_[0])/2),
00950 vy = ((*sf_iter)->velocity_[1]- ((*sf_iter)->velocity_[1] - other->velocity_[1])/2),
00951 vz = ((*sf_iter)->velocity_[2]- ((*sf_iter)->velocity_[2] - other->velocity_[2])/2);
00952
00953 double speed = sqrt(vx*vx + vy*vy + vz*vz);
00954
00955
00956 if (publish_people_ ){
00957
00958 reliability = reliability * other->reliability;
00959 cob_perception_msgs::PositionMeasurement pos;
00960 pos.header.stamp = (*sf_iter)->time_;
00961 pos.header.frame_id = fixed_frame;
00962 pos.name = (*sf_iter)->object_id;
00963 pos.object_id = (*sf_iter)->id_ + "|" + other->id_;
00964 pos.pos.x = dx;
00965 pos.pos.y = dy;
00966 pos.pos.z = dz;
00967 pos.vel.x = vx;
00968 pos.vel.y = vy;
00969 pos.vel.z = vz;
00970 pos.reliability = reliability;
00971 pos.covariance[0] = pow(0.3 / reliability,2.0);
00972 pos.covariance[1] = 0.0;
00973 pos.covariance[2] = 0.0;
00974 pos.covariance[3] = 0.0;
00975 pos.covariance[4] = pow(0.3 / reliability,2.0);
00976 pos.covariance[5] = 0.0;
00977 pos.covariance[6] = 0.0;
00978 pos.covariance[7] = 0.0;
00979 pos.covariance[8] = 10000.0;
00980 pos.initialization = 0;
00981
00982 people.push_back(pos);
00983
00984 ros::Time time = ros::Time::now();
00985 tf::Transform person(tf::Quaternion(0,0,0,1), tf::Vector3(dx, dy, dz));
00986 try
00987 {
00988 br_.sendTransform(tf::StampedTransform(person, time,
00989 "/base_link" , pos.name.c_str()));
00990 }catch (tf::TransformException ex){
00991 ROS_ERROR("Broadcaster unavailable %s", ex.what());
00992 }
00993 }
00994
00995 if (publish_people_markers_ ){
00996 visualization_msgs::Marker m;
00997 m.header.stamp = (*sf_iter)->time_;
00998 m.header.frame_id = fixed_frame;
00999 m.ns = "PEOPLE";
01000 m.id = i;
01001 m.type = m.SPHERE;
01002 m.pose.position.x = dx;
01003 m.pose.position.y = dy;
01004 m.pose.position.z = dz;
01005 m.scale.x = .2;
01006 m.scale.y = .2;
01007 m.scale.z = .2;
01008 m.color.a = 1;
01009 m.color.g = 1;
01010 m.lifetime = ros::Duration(0.5);
01011 markers_pub_.publish(m);
01012 }
01013
01014 if(publish_people_markers_ ){
01015 visualization_msgs::Marker m;
01016 m.header.stamp = (*sf_iter)->time_;
01017 m.header.frame_id = fixed_frame;
01018 m.ns = "TEXT";
01019 m.id = i;
01020 m.type = m.TEXT_VIEW_FACING;
01021 m.pose.position.x = dx;
01022 m.pose.position.y = dy;
01023 m.pose.position.z = dz;
01024 m.pose.orientation.w = 1.0;
01025 m.text = (*sf_iter)->object_id.c_str();
01026 m.scale.z = 0.3;
01027 m.color.a = 1;
01028 m.color.r = 0.5;
01029 m.color.g = 0.5;
01030 m.lifetime = ros::Duration(0.5);
01031 markers_pub_.publish(m);
01032 }
01033
01034
01035
01036
01037
01038
01039
01040
01041
01042
01043
01044
01045
01046
01047
01048
01049
01050
01051
01052
01053
01054
01055
01056
01057
01058 }
01059 }
01060 }
01061 cob_perception_msgs::PositionMeasurementArray array;
01062 array.header.stamp = ros::Time::now();
01063 array.header.frame_id = fixed_frame;
01064
01065 if(publish_legs_){
01066 array.people = legs;
01067 leg_measurements_pub_.publish(array);
01068 }
01069
01070 if(publish_people_){
01071 array.people = people;
01072 people_measurements_pub_.publish(array);
01073 }
01074 }
01075
01076
01077 double distance( list<SavedFeature*>::iterator it1, list<SavedFeature*>::iterator it2)
01078 {
01079 Stamped<Point> one = (*it1)->position_, two = (*it2)->position_;
01080 double dx = one[0]-two[0], dy = one[1]-two[1], dz = one[2]-two[2];
01081 return sqrt(dx*dx+dy*dy+dz*dz);
01082 }
01083
01084
01085 inline void PRINT_LIST (list<SavedPersonFeature*>& coll, const char* optcstr="")
01086 {
01087 std::cout << optcstr;
01088 for ( list<SavedPersonFeature*>::iterator it =coll.begin();it !=coll.end(); ++it) {
01089 std::cout << (*it)->person_name << ' ';
01090 }
01091 std::cout << std::endl;
01092 }
01093
01094
01095 void pairLegs()
01096 {
01097
01098 list<SavedFeature*>::iterator begin = saved_features_.begin();
01099 list<SavedFeature*>::iterator end = saved_features_.end();
01100 list<SavedFeature*>::iterator leg1, leg2, best, it;
01101
01102 for (leg1 = begin; leg1 != end; ++leg1){
01103
01104 if ((*leg1)->object_id == "")
01105 continue;
01106
01107 leg2 = end;
01108 best = end;
01109
01110
01111 double closest_dist = leg_pair_separation_m;
01112 for ( it = begin; it != end; ++it){
01113 if(it==leg1) continue;
01114
01115 if ( (*it)->object_id == (*leg1)->object_id ) {
01116 leg2 = it;
01117 break;
01118 }
01119
01120 if ((*it)->object_id != "")
01121 continue;
01122
01123 double d = distance(it, leg1);
01124 if (((*it)->getLifetime() <= max_second_leg_age_s)
01125 && (d < closest_dist)){
01126 closest_dist = d;
01127 best = it;
01128 }
01129 }
01130
01131 if(leg2 != end){
01132 double dist_between_legs = distance(leg1, leg2);
01133 if (dist_between_legs > leg_pair_separation_m){
01134 (*leg1)->object_id = "";
01135 (*leg1)->other = NULL;
01136 (*leg2)->object_id = "";
01137 (*leg2)->other = NULL;
01138 }else{
01139 (*leg1)->other = *leg2;
01140 (*leg2)->other = *leg1;
01141 }
01142 }else if(best != end){
01143 (*best)->object_id = (*leg1)->object_id;
01144 (*leg1)->other = *best;
01145 (*best)->other = *leg1;
01146
01147 }
01148 }
01149
01150
01151 for(;;){
01152 list<SavedFeature*>::iterator best1 = end, best2 = end;
01153 double closest_dist = leg_pair_separation_m;
01154
01155 for (leg1 = begin; leg1 != end; ++leg1){
01156
01157 if ((*leg1)->object_id != ""
01158 || (*leg1)->getReliability() < leg_reliability_limit_)
01159 continue;
01160
01161 for ( leg2 = begin; leg2 != end; ++leg2){
01162 if(((*leg2)->object_id != "")
01163 || ((*leg2)->getReliability() < leg_reliability_limit_)
01164 || (leg1==leg2)) continue;
01165
01166 double d = distance(leg1, leg2);
01167
01168 if(d < closest_dist){
01169 best1 = leg1;
01170 best2 = leg2;
01171 }
01172 }
01173 }
01174
01175 if(best1 != end){
01176 char id[100];
01177 float number = next_p_id_;
01178 snprintf(id,100,"Person%d", next_p_id_++);
01179 (*best1)->object_id = std::string(id);
01180 (*best2)->object_id = std::string(id);
01181 (*best1)->other = *best2;
01182 (*best2)->other = *best1;
01183 }else{
01184 break;
01185 }
01186 }
01187 }
01188 };
01189
01190 int main(int argc, char **argv)
01191 {
01192 ros::init(argc, argv,"leg_detection");
01193 g_argc = argc;
01194 g_argv = argv;
01195 ros::NodeHandle nh;
01196 LegDetector ld(nh);
01197 ROS_INFO("Execute main");
01198 ros::spin();
01199
01200 return 0;
01201 }