zerorate.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 
32 
33 namespace hector_pose_estimation {
34 
35 template class Measurement_<ZeroRateModel>;
36 
38 {
39  parameters().add("stddev", stddev_, 90.0*M_PI/180.0);
40  parameters().add("use_bias", use_bias_, std::string("gyro_bias"));
41 }
42 
44 
45 bool ZeroRateModel::init(PoseEstimation &estimator, Measurement &measurement, State &state)
46 {
47  if (!use_bias_.empty()) {
48  bias_ = state.getSubState<3,3>(use_bias_);
49  if (!bias_) {
50  ROS_ERROR("Could not find bias substate '%s' during initialization of zero rate pseudo measurement '%s'.", use_bias_.c_str(), measurement.getName().c_str());
51  return false;
52  }
53  } else {
54  bias_.reset();
55  }
56 
57  if (!bias_ && !state.rate()) {
58  ROS_WARN("Pseudo updating with zero rate is a no-op, as the state does not contain rates nor biases.");
59  // return false;
60  }
61 
62  return true;
63 }
64 
65 void ZeroRateModel::getMeasurementNoise(NoiseVariance& R, const State&, bool init)
66 {
67  if (init) {
68  R(0,0) = pow(stddev_, 2);
69  }
70 }
71 
72 void ZeroRateModel::getExpectedValue(MeasurementVector& y_pred, const State& state)
73 {
74  y_pred(0) = state.getRate().z();
75 
76  if (!state.rate() && bias_) {
77  y_pred(0) += bias_->getVector().z();
78  }
79 }
80 
81 void ZeroRateModel::getStateJacobian(MeasurementMatrix& C, const State& state, bool)
82 {
83  if (state.rate()) {
84  state.rate()->cols(C)(0,Z) = 1.0;
85  } else if (bias_) {
86  bias_->cols(C)(0,Z) = 1.0;
87  }
88 }
89 
90 const ZeroRateModel::MeasurementVector* ZeroRateModel::getFixedMeasurementVector() const
91 {
92  static MeasurementVector zero(MeasurementVector::Zero());
93  return &zero;
94 }
95 
96 } // 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 ConstRateType getRate() const
Definition: state.cpp:117
Block< MatrixType, MatrixType::RowsAtCompileTime, CovarianceDimension > cols(MatrixType &matrix)
Definition: substate.h:129
virtual bool init(PoseEstimation &estimator, Measurement &measurement, State &state)
Definition: zerorate.cpp:45
#define ROS_WARN(...)
ParameterList & add(const std::string &key, T &value, const T &default_value)
Definition: parameters.h:148
ParameterList & parameters()
Definition: model.h:47
virtual void getMeasurementNoise(NoiseVariance &R, const State &, bool init)
Definition: zerorate.cpp:65
virtual void getStateJacobian(MeasurementMatrix &C, const State &state, bool init)
Definition: zerorate.cpp:81
virtual const boost::shared_ptr< RateStateType > & rate() const
Definition: state.h:113
virtual void getExpectedValue(MeasurementVector &y_pred, const State &state)
Definition: zerorate.cpp:72
#define ROS_ERROR(...)
const MeasurementVector * getFixedMeasurementVector() const
Definition: zerorate.cpp:90


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