rate.cpp
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2011, Johannes Meyer, TU Darmstadt
3 // All rights reserved.
4 
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of the Flight Systems and Automatic Control group,
13 // TU Darmstadt, nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //=================================================================================================
28 
31 
32 namespace hector_pose_estimation {
33 
34 template class Measurement_<RateModel>;
35 
37 {
38  parameters().add("stddev", stddev_, 10.0 * M_PI/180.0);
39  parameters().add("use_bias", use_bias_, std::string("gyro_bias"));
40 }
41 
43 
44 bool RateModel::init(PoseEstimation &estimator, Measurement &measurement, State &state)
45 {
46  if (!use_bias_.empty()) {
47  bias_ = state.getSubState<3,3>(use_bias_);
48  if (!bias_) {
49  ROS_ERROR("Could not find bias substate '%s' during initialization of rate measurement '%s'.", use_bias_.c_str(), measurement.getName().c_str());
50  return false;
51  }
52  } else {
53  bias_.reset();
54  }
55 
56  return true;
57 }
58 
59 void RateModel::getMeasurementNoise(NoiseVariance& R, const State&, bool init)
60 {
61  if (init) {
62  R(0,0) = R(1,1) = R(2,2) = pow(stddev_, 2);
63  }
64 }
65 
66 void RateModel::getExpectedValue(MeasurementVector& y_pred, const State& state)
67 {
68  y_pred = state.getRate();
69 
70  if (bias_) {
71  y_pred += bias_->getVector();
72  }
73 }
74 
75 void RateModel::getStateJacobian(MeasurementMatrix &C, const State &state, bool init)
76 {
77  if (!init) return;
78 
79  if (state.rate()) {
80  state.rate()->cols(C).setIdentity();
81  }
82 
83  if (bias_) {
84  bias_->cols(C).setIdentity();
85  }
86 }
87 
88 } // namespace hector_pose_estimation
boost::shared_ptr< SubState_< SubVectorDimension, SubCovarianceDimension > > getSubState(const Model *model) const
ConstVectorSegment getVector() const
Definition: substate.h:116
virtual const std::string & getName() const
Definition: measurement.h:50
virtual bool init(PoseEstimation &estimator, Measurement &measurement, State &state)
Definition: rate.cpp:44
virtual ConstRateType getRate() const
Definition: state.cpp:117
virtual void getExpectedValue(MeasurementVector &y_pred, const State &state)
Definition: rate.cpp:66
SubState_< 3 >::Ptr bias_
Definition: rate.h:52
Block< MatrixType, MatrixType::RowsAtCompileTime, CovarianceDimension > cols(MatrixType &matrix)
Definition: substate.h:129
ParameterList & add(const std::string &key, T &value, const T &default_value)
Definition: parameters.h:148
ParameterList & parameters()
Definition: model.h:47
virtual void getStateJacobian(MeasurementMatrix &C, const State &state, bool init)
Definition: rate.cpp:75
virtual const boost::shared_ptr< RateStateType > & rate() const
Definition: state.h:113
virtual void getMeasurementNoise(NoiseVariance &R, const State &, bool init)
Definition: rate.cpp:59
#define ROS_ERROR(...)


hector_pose_estimation_core
Author(s): Johannes Meyer
autogenerated on Thu Feb 18 2021 03:29:30