$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2008, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00035 /* Author: Wim Meeussen */ 00036 /* Modified for SRS: Alex Noyvirt */ 00037 00038 #include "srs_people_tracking_filter/detector_particle.h" 00039 #include "srs_people_tracking_filter/uniform_vector.h" 00040 00041 using namespace MatrixWrapper; 00042 using namespace BFL; 00043 using namespace tf; 00044 using namespace std; 00045 using namespace ros; 00046 using namespace geometry_msgs; 00047 00048 00049 00050 00051 namespace estimation 00052 { 00053 // constructor 00054 DetectorParticle::DetectorParticle(unsigned int num_particles): 00055 prior_(num_particles), 00056 filter_(NULL), 00057 sys_model_(tf::Vector3(0.1,0.1,0.1)), 00058 meas_model_(tf::Vector3(0.1,0.1,0.1)), 00059 detector_initialized_(false), 00060 num_particles_(num_particles) 00061 {} 00062 00063 00064 00065 // destructor 00066 DetectorParticle::~DetectorParticle(){ 00067 if (filter_) delete filter_; 00068 } 00069 00070 00071 // initialize prior density of filter 00072 void DetectorParticle::initialize(const tf::Vector3& mu, const tf::Vector3& size, const double time) 00073 { 00074 cout << "Initializing detector with " << num_particles_ << " particles, with uniform size " 00075 << size << " around " << mu << endl; 00076 00077 UniformVector uniform_vector(mu, size); 00078 vector<Sample<tf::Vector3> > prior_samples(num_particles_); 00079 uniform_vector.SampleFrom(prior_samples, num_particles_, CHOLESKY, NULL); 00080 prior_.ListOfSamplesSet(prior_samples); 00081 filter_ = new BootstrapFilter<tf::Vector3, tf::Vector3>(&prior_, &prior_, 0, num_particles_/4.0); 00082 00083 // detector initialized 00084 detector_initialized_ = true; 00085 quality_ = 1; 00086 filter_time_ = time; 00087 } 00088 00089 00090 00091 00092 // update filter prediction 00093 bool DetectorParticle::updatePrediction(const double dt) 00094 { 00095 // set de in sys model 00096 sys_model_.SetDt(dt); 00097 00098 // update filter 00099 bool res = filter_->Update(&sys_model_); 00100 if (!res) quality_ = 0; 00101 00102 return res; 00103 } 00104 00105 00106 00107 // update filter correction 00108 bool DetectorParticle::updateCorrection(const tf::Vector3& meas, const MatrixWrapper::SymmetricMatrix& cov, const double time) 00109 { 00110 assert(cov.columns() == 3); 00111 00112 // set filter time 00113 filter_time_ = time; 00114 00115 // set covariance 00116 ((MeasPdfVector*)(meas_model_.MeasurementPdfGet()))->CovarianceSet(cov); 00117 00118 // update filter 00119 bool res = filter_->Update(&meas_model_, meas); 00120 if (!res) quality_ = 0; 00121 00122 return res; 00123 } 00124 00125 00126 // get evenly spaced particle cloud 00127 void DetectorParticle::getParticleCloud(const tf::Vector3& step, double threshold, sensor_msgs::PointCloud& cloud) const 00128 { 00129 ((MCPdfVector*)(filter_->PostGet()))->getParticleCloud(step, threshold, cloud); 00130 } 00131 00132 00133 // get most recent filter posterior 00134 void DetectorParticle::getEstimate(tf::Vector3& est) const 00135 { 00136 est = ((MCPdfVector*)(filter_->PostGet()))->ExpectedValueGet(); 00137 } 00138 00139 00140 void DetectorParticle::getEstimate(srs_msgs::PositionMeasurement& est) const 00141 { 00142 tf::Vector3 tmp = filter_->PostGet()->ExpectedValueGet(); 00143 00144 est.pos.x = tmp[0]; 00145 est.pos.y = tmp[1]; 00146 est.pos.z = tmp[2]; 00147 00148 est.header.stamp.fromSec( filter_time_ ); 00149 est.header.frame_id = "base_link"; 00150 } 00151 00152 00153 00154 00155 00157 Matrix DetectorParticle::getHistogram(const tf::Vector3& min, const tf::Vector3& max, const tf::Vector3& step) const 00158 { 00159 return ((MCPdfVector*)(filter_->PostGet()))->getHistogram(min, max, step); 00160 } 00161 00162 00163 }; // namespace 00164 00165 00166