sysmodel_pos_vel.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 
38 
39 namespace BFL
40 {
41 
42 static const unsigned int NUM_SYS_POS_VEL_COND_ARGS = 1;
43 static const unsigned int DIM_SYS_POS_VEL = 6;
44 
45 // Constructor
47  : ConditionalPdf<StatePosVel, StatePosVel>(DIM_SYS_POS_VEL, NUM_SYS_POS_VEL_COND_ARGS),
48  noise_(StatePosVel(tf::Vector3(0, 0, 0), tf::Vector3(0, 0, 0)), sigma)
49 {}
50 
51 // Destructor
53 {}
54 
57 {
58  std::cerr << "SysPdfPosVel::ProbabilityGet Method not applicable" << std::endl;
59  assert(0);
60  return 0;
61 }
62 
63 bool
64 SysPdfPosVel::SampleFrom(Sample<StatePosVel>& one_sample, int method, void *args) const
65 {
66  StatePosVel& res = one_sample.ValueGet();
67 
68  // get conditional argument: state
69  res = this->ConditionalArgumentGet(0);
70 
71  // apply system model
72  res.pos_ += (res.vel_ * dt_);
73 
74  // add noise
75  Sample<StatePosVel> noise_sample;
76  noise_.SetDt(dt_);
77  noise_.SampleFrom(noise_sample, method, args);
78  res += noise_sample.ValueGet();
79 
80  return true;
81 }
82 
85 {
86  std::cerr << "SysPdfPosVel::ExpectedValueGet Method not applicable" << std::endl;
87  assert(0);
88  return StatePosVel();
89 }
90 
91 SymmetricMatrix
93 {
94  std::cerr << "SysPdfPosVel::CovarianceGet Method not applicable" << std::endl;
95  SymmetricMatrix Covar(DIM_SYS_POS_VEL);
96  assert(0);
97  return Covar;
98 }
99 } // namespace BFL
static const unsigned int DIM_SYS_POS_VEL
Class representing state with pos and vel.
Definition: state_pos_vel.h:46
GaussianPosVel noise_
virtual StatePosVel ExpectedValueGet() const
virtual Probability ProbabilityGet(const StatePosVel &state) const
SysPdfPosVel(const StatePosVel &sigma)
Constructor.
void SetDt(double dt) const
virtual bool SampleFrom(BFL::Sample< StatePosVel > &one_sample, int method, void *args) const
TFSIMD_FORCE_INLINE Vector3()
virtual MatrixWrapper::SymmetricMatrix CovarianceGet() const
const StatePosVel & ConditionalArgumentGet(unsigned int n_argument) const
T & ValueGet()
tf::Vector3 vel_
Definition: state_pos_vel.h:49
virtual ~SysPdfPosVel()
Destructor.
tf::Vector3 pos_
Definition: state_pos_vel.h:49
bool SampleFrom(vector< Sample< StatePosVel > > &list_samples, const int num_samples, int method=DEFAULT, void *args=NULL) const
static const unsigned int NUM_SYS_POS_VEL_COND_ARGS


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