gaussian_pos_vel.cpp
Go to the documentation of this file.
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 
00037 
00038 #include "cob_people_tracking_filter/gaussian_pos_vel.h"
00039 #include <wrappers/rng/rng.h>
00040 #include <cmath> 
00041 #include <cassert>
00042 
00043 using namespace tf;
00044 
00045 namespace BFL
00046 {
00047   GaussianPosVel::GaussianPosVel (const StatePosVel& mu, const StatePosVel& sigma)
00048     : Pdf<StatePosVel> ( 1 ),
00049       mu_(mu),
00050       sigma_(sigma),
00051       gauss_pos_(mu.pos_, sigma.pos_),
00052       gauss_vel_(mu.vel_, sigma.vel_)
00053   {}
00054 
00055 
00056   GaussianPosVel::~GaussianPosVel(){}
00057 
00058   GaussianPosVel* GaussianPosVel::Clone() const
00059   {
00060     return new GaussianPosVel(mu_, sigma_);
00061   }
00062 
00063   std::ostream& operator<< (std::ostream& os, const GaussianPosVel& g)
00064   {
00065     os << "\nMu pos :\n"    << g.ExpectedValueGet().pos_ << endl
00066        << "\nMu vel :\n"    << g.ExpectedValueGet().vel_ << endl 
00067        << "\nSigma:\n" << g.CovarianceGet() << endl;
00068     return os;
00069   }
00070 
00071 
00072   Probability GaussianPosVel::ProbabilityGet(const StatePosVel& input) const
00073   {
00074     return gauss_pos_.ProbabilityGet(input.pos_) * gauss_vel_.ProbabilityGet(input.vel_);
00075   }
00076 
00077 
00078   bool
00079   GaussianPosVel::SampleFrom (vector<Sample<StatePosVel> >& list_samples, const int num_samples, int method, void * args) const
00080   {
00081     list_samples.resize(num_samples);
00082     vector<Sample<StatePosVel> >::iterator sample_it = list_samples.begin();
00083     for (sample_it=list_samples.begin(); sample_it!=list_samples.end(); sample_it++)
00084       SampleFrom( *sample_it, method, args);
00085 
00086     return true;
00087   }
00088 
00089 
00090   bool
00091   GaussianPosVel::SampleFrom (Sample<StatePosVel>& one_sample, int method, void * args) const
00092   {
00093     one_sample.ValueSet( StatePosVel(Vector3(rnorm(mu_.pos_[0], sigma_.pos_[0]*dt_), 
00094                                              rnorm(mu_.pos_[1], sigma_.pos_[1]*dt_),
00095                                              rnorm(mu_.pos_[2], sigma_.pos_[2]*dt_)),
00096                                      Vector3(rnorm(mu_.vel_[0], sigma_.vel_[0]*dt_), 
00097                                              rnorm(mu_.vel_[1], sigma_.vel_[1]*dt_),
00098                                              rnorm(mu_.vel_[2], sigma_.vel_[2]*dt_))) );
00099     return true;
00100   }
00101 
00102 
00103   StatePosVel
00104   GaussianPosVel::ExpectedValueGet (  ) const 
00105   { 
00106     return mu_;
00107   }
00108 
00109   SymmetricMatrix
00110   GaussianPosVel::CovarianceGet () const
00111   {
00112     SymmetricMatrix sigma(6); sigma = 0;
00113     for (unsigned int i=0; i<3; i++){
00114       sigma(i+1,i+1) = pow(sigma_.pos_[i],2);
00115       sigma(i+4,i+4) = pow(sigma_.vel_[i],2);
00116     }
00117     return sigma;
00118   }
00119 
00120 } // End namespace BFL


cob_people_tracking_filter
Author(s): Caroline Pantofaru, Olha Meyer
autogenerated on Mon May 6 2019 02:32:13