tracker_kalman.h
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 
37 #ifndef PEOPLE_TRACKING_FILTER_TRACKER_KALMAN_H
38 #define PEOPLE_TRACKING_FILTER_TRACKER_KALMAN_H
39 
41 
42 // bayesian filtering
43 #include <bfl/filter/extendedkalmanfilter.h>
44 #include <bfl/model/linearanalyticsystemmodel_gaussianuncertainty.h>
45 #include <bfl/model/linearanalyticmeasurementmodel_gaussianuncertainty.h>
46 #include <bfl/pdf/linearanalyticconditionalgaussian.h>
47 
48 
50 
51 // TF
52 #include <tf/tf.h>
53 
54 // log files
55 #include <fstream>
56 #include <string>
57 
58 namespace estimation
59 {
60 
61 class TrackerKalman: public Tracker
62 {
63 public:
65  TrackerKalman(const std::string& name, const BFL::StatePosVel& sysnoise);
66 
68  virtual ~TrackerKalman();
69 
71  virtual void initialize(const BFL::StatePosVel& mu, const BFL::StatePosVel& sigma, const double time);
72 
74  virtual bool isInitialized() const
75  {
76  return tracker_initialized_;
77  };
78 
80  virtual double getQuality() const
81  {
82  return quality_;
83  };
84 
86  virtual double getLifetime() const;
87 
89  virtual double getTime() const;
90 
92  virtual bool updatePrediction(const double time);
93  virtual bool updateCorrection(const tf::Vector3& meas,
94  const MatrixWrapper::SymmetricMatrix& cov);
95 
97  virtual void getEstimate(BFL::StatePosVel& est) const;
98  virtual void getEstimate(people_msgs::PositionMeasurement& est) const;
99 
100 private:
101  // pdf / model / filter
108  MatrixWrapper::Matrix sys_matrix_;
109  MatrixWrapper::SymmetricMatrix sys_sigma_;
110 
111  double calculateQuality();
112 
113  // vars
116 }; // class
117 } // namespace estimation
118 #endif // PEOPLE_TRACKING_FILTER_TRACKER_KALMAN_H
virtual void getEstimate(BFL::StatePosVel &est) const
get filter posterior
virtual double getTime() const
return the time of the tracker
virtual bool isInitialized() const
return if tracker was initialized
virtual double getLifetime() const
return the lifetime of the tracker
BFL::ExtendedKalmanFilter * filter_
Class representing state with pos and vel.
Definition: state_pos_vel.h:46
BFL::LinearAnalyticMeasurementModelGaussianUncertainty * meas_model_
BFL::LinearAnalyticSystemModelGaussianUncertainty * sys_model_
virtual ~TrackerKalman()
destructor
virtual void initialize(const BFL::StatePosVel &mu, const BFL::StatePosVel &sigma, const double time)
initialize tracker
MatrixWrapper::Matrix sys_matrix_
BFL::LinearAnalyticConditionalGaussian * meas_pdf_
BFL::LinearAnalyticConditionalGaussian * sys_pdf_
virtual bool updateCorrection(const tf::Vector3 &meas, const MatrixWrapper::SymmetricMatrix &cov)
virtual double getQuality() const
return measure for tracker quality: 0=bad 1=good
MatrixWrapper::SymmetricMatrix sys_sigma_
virtual bool updatePrediction(const double time)
update tracker
TrackerKalman(const std::string &name, const BFL::StatePosVel &sysnoise)
constructor


people_tracking_filter
Author(s): Caroline Pantofaru
autogenerated on Sun Feb 21 2021 03:56:47