detector_particle.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 
35 /* Author: Wim Meeussen */
36 
39 
40 using namespace MatrixWrapper;
41 using namespace BFL;
42 using namespace tf;
43 using namespace std;
44 using namespace ros;
45 using namespace geometry_msgs;
46 
47 
48 
49 
50 namespace estimation
51 {
52 // constructor
53 DetectorParticle::DetectorParticle(unsigned int num_particles):
54  prior_(num_particles),
55  filter_(NULL),
56  sys_model_(tf::Vector3(0.1, 0.1, 0.1)),
57  meas_model_(tf::Vector3(0.1, 0.1, 0.1)),
58  detector_initialized_(false),
59  num_particles_(num_particles)
60 {}
61 
62 
63 
64 // destructor
66 {
67  if (filter_) delete filter_;
68 }
69 
70 
71 // initialize prior density of filter
72 void DetectorParticle::initialize(const tf::Vector3& mu, const tf::Vector3& size, const double time)
73 {
74  cout << "Initializing detector with " << num_particles_ << " particles, with uniform size "
75  << size << " around " << mu << endl;
76 
77  UniformVector uniform_vector(mu, size);
78  vector<Sample<tf::Vector3> > prior_samples(num_particles_);
79  uniform_vector.SampleFrom(prior_samples, num_particles_, CHOLESKY, NULL);
80  prior_.ListOfSamplesSet(prior_samples);
81  filter_ = new BootstrapFilter<tf::Vector3, tf::Vector3>(&prior_, &prior_, 0, num_particles_ / 4.0);
82 
83  // detector initialized
84  detector_initialized_ = true;
85  quality_ = 1;
86  filter_time_ = time;
87 }
88 
89 
90 
91 
92 // update filter prediction
94 {
95  // set de in sys model
96  sys_model_.SetDt(dt);
97 
98  // update filter
99  bool res = filter_->Update(&sys_model_);
100  if (!res) quality_ = 0;
101 
102  return res;
103 }
104 
105 
106 
107 // update filter correction
108 bool DetectorParticle::updateCorrection(const tf::Vector3& meas, const MatrixWrapper::SymmetricMatrix& cov, const double time)
109 {
110  assert(cov.columns() == 3);
111 
112  // set filter time
113  filter_time_ = time;
114 
115  // set covariance
116  ((MeasPdfVector*)(meas_model_.MeasurementPdfGet()))->CovarianceSet(cov);
117 
118  // update filter
119  bool res = filter_->Update(&meas_model_, meas);
120  if (!res) quality_ = 0;
121 
122  return res;
123 }
124 
125 
126 // get evenly spaced particle cloud
127 void DetectorParticle::getParticleCloud(const tf::Vector3& step, double threshold, sensor_msgs::PointCloud& cloud) const
128 {
129  ((MCPdfVector*)(filter_->PostGet()))->getParticleCloud(step, threshold, cloud);
130 }
131 
132 
133 // get most recent filter posterior
135 {
136  est = ((MCPdfVector*)(filter_->PostGet()))->ExpectedValueGet();
137 }
138 
139 
140 void DetectorParticle::getEstimate(people_msgs::PositionMeasurement& est) const
141 {
142  tf::Vector3 tmp = filter_->PostGet()->ExpectedValueGet();
143 
144  est.pos.x = tmp[0];
145  est.pos.y = tmp[1];
146  est.pos.z = tmp[2];
147 
148  est.header.stamp.fromSec(filter_time_);
149  est.header.frame_id = "base_link";
150 }
151 
152 
153 
154 
155 
157 Matrix DetectorParticle::getHistogram(const tf::Vector3& min, const tf::Vector3& max, const tf::Vector3& step) const
158 {
159  return ((MCPdfVector*)(filter_->PostGet()))->getHistogram(min, max, step);
160 }
161 
162 
163 }; // namespace
164 
165 
166 
void getParticleCloud(const tf::Vector3 &step, double threshold, sensor_msgs::PointCloud &cloud) const
Class representing uniform vector.
void getEstimate(tf::Vector3 &est) const
get filter posterior
bool SampleFrom(vector< Sample< tf::Vector3 > > &list_samples, const int num_samples, int method=DEFAULT, void *args=NULL) const
void SetDt(double dt)
TFSIMD_FORCE_INLINE const tfScalar & z() const
BFL::BootstrapFilter< tf::Vector3, tf::Vector3 > * filter_
TFSIMD_FORCE_INLINE const tfScalar & y() const
Class representing a vector mcpdf.
Definition: mcpdf_vector.h:47
BFL::MeasModelVector meas_model_
bool updatePrediction(const double dt)
update detector
MatrixWrapper::Matrix getHistogram(const tf::Vector3 &min, const tf::Vector3 &max, const tf::Vector3 &step) const
Get histogram from certain area.
bool updateCorrection(const tf::Vector3 &meas, const MatrixWrapper::SymmetricMatrix &cov, const double time)
void initialize(const tf::Vector3 &mu, const tf::Vector3 &size, const double time)
initialize detector
BFL::SysModelVector sys_model_


people_tracking_filter
Author(s): Caroline Pantofaru
autogenerated on Fri Jun 7 2019 22:07:49