poseupdate.h
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 
29 #ifndef HECTOR_POSE_ESTIMATION_POSEUPDATE_H
30 #define HECTOR_POSE_ESTIMATION_POSEUPDATE_H
31 
33 #include <geometry_msgs/PoseWithCovarianceStamped.h>
34 #include <geometry_msgs/TwistWithCovarianceStamped.h>
35 
36 #include <boost/function.hpp>
37 
38 namespace hector_pose_estimation {
39 
40 class PositionXYModel : public MeasurementModel_<PositionXYModel,2> {
41 public:
43  virtual ~PositionXYModel() {}
44 
45  virtual void getExpectedValue(MeasurementVector& y_pred, const State& state);
46  virtual void getStateJacobian(MeasurementMatrix& C, const State& state, bool init);
47 
48  void updateState(State& state, const ColumnVector &diff) const;
49 };
50 
51 class PositionZModel : public MeasurementModel_<PositionZModel,1> {
52 public:
54  virtual ~PositionZModel() {}
55 
56  virtual void getExpectedValue(MeasurementVector& y_pred, const State& state);
57  virtual void getStateJacobian(MeasurementMatrix& C, const State& state, bool init);
58 
59  void updateState(State& state, const ColumnVector &diff) const;
60 };
61 
62 class YawModel : public MeasurementModel_<YawModel,1> {
63 public:
64  YawModel() {}
65  virtual ~YawModel() {}
66 
67  virtual void getExpectedValue(MeasurementVector& y_pred, const State& state);
68  virtual void getStateJacobian(MeasurementMatrix& C, const State& state, bool init);
69 
70  void updateState(State& state, const ColumnVector &diff) const;
71 };
72 
73 class TwistModel : public MeasurementModel_<TwistModel,6> {
74 public:
76  virtual ~TwistModel() {}
77 
78  virtual void getExpectedValue(MeasurementVector& y_pred, const State& state);
79  virtual void getStateJacobian(MeasurementMatrix& C, const State& state, bool init);
80 };
81 
82 class PoseUpdate : public Measurement
83 {
84 public:
85  PoseUpdate(const std::string& name = "poseupdate");
86  virtual ~PoseUpdate();
87 
88  class Update : public MeasurementUpdate {
89  public:
90  Update() {}
91  Update(const geometry_msgs::PoseWithCovarianceStamped& pose) : pose(new geometry_msgs::PoseWithCovarianceStamped(pose)) {}
92  Update(const geometry_msgs::PoseWithCovarianceStampedConstPtr& pose) : pose(pose) {}
93  Update(const geometry_msgs::TwistWithCovarianceStamped& twist) : twist(new geometry_msgs::TwistWithCovarianceStamped(twist)) {}
94  Update(const geometry_msgs::TwistWithCovarianceStampedConstPtr& twist) : twist(twist) {}
95  Update(const geometry_msgs::PoseWithCovarianceStamped& pose, const geometry_msgs::TwistWithCovarianceStamped& twist) : pose(new geometry_msgs::PoseWithCovarianceStamped(pose)), twist(new geometry_msgs::TwistWithCovarianceStamped(twist)) {}
96  Update(const geometry_msgs::PoseWithCovarianceStampedConstPtr& pose, const geometry_msgs::TwistWithCovarianceStampedConstPtr& twist) : pose(pose), twist(twist) {}
97  geometry_msgs::PoseWithCovarianceStampedConstPtr pose;
98  geometry_msgs::TwistWithCovarianceStampedConstPtr twist;
99  };
100 
101  virtual bool updateImpl(const MeasurementUpdate &update);
102 
103 private:
108 
114 
118 
123 
127 
132 
133  typedef boost::function<void(State &state, const ColumnVector &diff)> JumpFunction;
134  double calculateOmega(const SymmetricMatrix &Ix, const SymmetricMatrix &Iy);
135 
136  template <typename MeasurementVector, typename MeasurementMatrix, typename NoiseVariance>
137  double updateInternal(State &state, const NoiseVariance &Iy, const MeasurementVector &error, const MeasurementMatrix &H, const std::string& text, const double max_error = 0.0, JumpFunction jump_function = JumpFunction());
138 
139 protected:
141  virtual Queue& queue() { return queue_; }
142 };
143 
144 } // namespace hector_pose_estimation
145 
146 #endif // HECTOR_POSE_ESTIMATION_POSEUPDATE_H
hector_pose_estimation::Measurement::update
virtual bool update(const MeasurementUpdate &update)
Definition: measurement.cpp:110
hector_pose_estimation::PoseUpdate::max_yaw_error_
double max_yaw_error_
Definition: poseupdate.h:126
hector_pose_estimation::YawModel::getExpectedValue
virtual void getExpectedValue(MeasurementVector &y_pred, const State &state)
Definition: poseupdate.cpp:454
hector_pose_estimation::PoseUpdate
Definition: poseupdate.h:82
hector_pose_estimation::PoseUpdate::fixed_angular_rate_z_stddev_
double fixed_angular_rate_z_stddev_
Definition: poseupdate.h:122
hector_pose_estimation::PoseUpdate::Update::pose
geometry_msgs::PoseWithCovarianceStampedConstPtr pose
Definition: poseupdate.h:97
hector_pose_estimation::PoseUpdate::Update::Update
Update(const geometry_msgs::PoseWithCovarianceStamped &pose)
Definition: poseupdate.h:91
hector_pose_estimation::PoseUpdate::position_z_model_
PositionZModel position_z_model_
Definition: poseupdate.h:105
hector_pose_estimation::PoseUpdate::max_velocity_z_error_
double max_velocity_z_error_
Definition: poseupdate.h:129
hector_pose_estimation::PoseUpdate::calculateOmega
double calculateOmega(const SymmetricMatrix &Ix, const SymmetricMatrix &Iy)
Definition: poseupdate.cpp:352
hector_pose_estimation::PositionZModel::getStateJacobian
virtual void getStateJacobian(MeasurementMatrix &C, const State &state, bool init)
Definition: poseupdate.cpp:442
hector_pose_estimation::State
Definition: state.h:42
geometry_msgs
hector_pose_estimation::PositionXYModel::getStateJacobian
virtual void getStateJacobian(MeasurementMatrix &C, const State &state, bool init)
Definition: poseupdate.cpp:423
hector_pose_estimation::PoseUpdate::~PoseUpdate
virtual ~PoseUpdate()
Definition: poseupdate.cpp:91
hector_pose_estimation::TwistModel::~TwistModel
virtual ~TwistModel()
Definition: poseupdate.h:76
hector_pose_estimation::PoseUpdate::Update::Update
Update()
Definition: poseupdate.h:90
hector_pose_estimation::ColumnVector
ColumnVector_< Dynamic >::type ColumnVector
Definition: matrix.h:58
hector_pose_estimation::PositionXYModel::updateState
void updateState(State &state, const ColumnVector &diff) const
Definition: poseupdate.cpp:432
hector_pose_estimation::SymmetricMatrix
SymmetricMatrix_< Dynamic >::type SymmetricMatrix
Definition: matrix.h:88
hector_pose_estimation::PoseUpdate::Update::Update
Update(const geometry_msgs::TwistWithCovarianceStamped &twist)
Definition: poseupdate.h:93
hector_pose_estimation::PoseUpdate::Update
Definition: poseupdate.h:88
hector_pose_estimation::PoseUpdate::max_time_difference_
double max_time_difference_
Definition: poseupdate.h:111
hector_pose_estimation::PoseUpdate::Update::Update
Update(const geometry_msgs::PoseWithCovarianceStampedConstPtr &pose)
Definition: poseupdate.h:92
hector_pose_estimation::PoseUpdate::queue
virtual Queue & queue()
Definition: poseupdate.h:141
hector_pose_estimation::PoseUpdate::max_angular_rate_z_error_
double max_angular_rate_z_error_
Definition: poseupdate.h:131
hector_pose_estimation::PoseUpdate::predict_pose_
bool predict_pose_
Definition: poseupdate.h:112
hector_pose_estimation::PoseUpdate::PoseUpdate
PoseUpdate(const std::string &name="poseupdate")
Definition: poseupdate.cpp:38
hector_pose_estimation::PoseUpdate::Update::Update
Update(const geometry_msgs::PoseWithCovarianceStamped &pose, const geometry_msgs::TwistWithCovarianceStamped &twist)
Definition: poseupdate.h:95
hector_pose_estimation::PoseUpdate::Update::Update
Update(const geometry_msgs::TwistWithCovarianceStampedConstPtr &twist)
Definition: poseupdate.h:94
hector_pose_estimation::PoseUpdate::updateInternal
double updateInternal(State &state, const NoiseVariance &Iy, const MeasurementVector &error, const MeasurementMatrix &H, const std::string &text, const double max_error=0.0, JumpFunction jump_function=JumpFunction())
Definition: poseupdate.cpp:359
hector_pose_estimation::PoseUpdate::Update::twist
geometry_msgs::TwistWithCovarianceStampedConstPtr twist
Definition: poseupdate.h:98
hector_pose_estimation::PoseUpdate::fixed_position_xy_stddev_
double fixed_position_xy_stddev_
Definition: poseupdate.h:115
hector_pose_estimation::PoseUpdate::twist_model_
TwistModel twist_model_
Definition: poseupdate.h:107
hector_pose_estimation::PoseUpdate::fixed_angular_rate_xy_stddev_
double fixed_angular_rate_xy_stddev_
Definition: poseupdate.h:121
hector_pose_estimation::PoseUpdate::Update::Update
Update(const geometry_msgs::PoseWithCovarianceStampedConstPtr &pose, const geometry_msgs::TwistWithCovarianceStampedConstPtr &twist)
Definition: poseupdate.h:96
hector_pose_estimation::TwistModel::TwistModel
TwistModel()
Definition: poseupdate.h:75
hector_pose_estimation::Measurement
Definition: measurement.h:42
hector_pose_estimation::YawModel::getStateJacobian
virtual void getStateJacobian(MeasurementMatrix &C, const State &state, bool init)
Definition: poseupdate.cpp:458
hector_pose_estimation::MeasurementModel_
Definition: measurement_model.h:52
hector_pose_estimation::PositionZModel::PositionZModel
PositionZModel()
Definition: poseupdate.h:53
hector_pose_estimation
Definition: collection.h:39
hector_pose_estimation::TwistModel
Definition: poseupdate.h:73
measurement.h
hector_pose_estimation::PositionXYModel::PositionXYModel
PositionXYModel()
Definition: poseupdate.h:42
hector_pose_estimation::PositionXYModel::~PositionXYModel
virtual ~PositionXYModel()
Definition: poseupdate.h:43
hector_pose_estimation::PoseUpdate::fixed_yaw_stddev_
double fixed_yaw_stddev_
Definition: poseupdate.h:117
hector_pose_estimation::Queue
Definition: queue.h:37
hector_pose_estimation::YawModel::~YawModel
virtual ~YawModel()
Definition: poseupdate.h:65
hector_pose_estimation::PoseUpdate::queue_
Queue_< Update > queue_
Definition: poseupdate.h:140
hector_pose_estimation::PoseUpdate::interpret_covariance_as_information_matrix_
bool interpret_covariance_as_information_matrix_
Definition: poseupdate.h:110
hector_pose_estimation::PoseUpdate::JumpFunction
boost::function< void(State &state, const ColumnVector &diff)> JumpFunction
Definition: poseupdate.h:133
hector_pose_estimation::PoseUpdate::jump_on_max_error_
bool jump_on_max_error_
Definition: poseupdate.h:113
hector_pose_estimation::PositionZModel::getExpectedValue
virtual void getExpectedValue(MeasurementVector &y_pred, const State &state)
Definition: poseupdate.cpp:438
hector_pose_estimation::PositionXYModel::getExpectedValue
virtual void getExpectedValue(MeasurementVector &y_pred, const State &state)
Definition: poseupdate.cpp:419
hector_pose_estimation::PositionXYModel
Definition: poseupdate.h:40
hector_pose_estimation::PoseUpdate::max_position_xy_error_
double max_position_xy_error_
Definition: poseupdate.h:124
hector_pose_estimation::YawModel::updateState
void updateState(State &state, const ColumnVector &diff) const
Definition: poseupdate.cpp:464
hector_pose_estimation::TwistModel::getStateJacobian
virtual void getStateJacobian(MeasurementMatrix &C, const State &state, bool init)
Definition: poseupdate.cpp:501
hector_pose_estimation::PoseUpdate::fixed_beta_
double fixed_beta_
Definition: poseupdate.h:109
hector_pose_estimation::MeasurementUpdate
Definition: measurement_update.h:36
hector_pose_estimation::PoseUpdate::yaw_model_
YawModel yaw_model_
Definition: poseupdate.h:106
hector_pose_estimation::Queue_
Definition: queue.h:53
hector_pose_estimation::PositionZModel::updateState
void updateState(State &state, const ColumnVector &diff) const
Definition: poseupdate.cpp:448
hector_pose_estimation::PositionZModel
Definition: poseupdate.h:51
hector_pose_estimation::PoseUpdate::fixed_velocity_xy_stddev_
double fixed_velocity_xy_stddev_
Definition: poseupdate.h:119
hector_pose_estimation::YawModel
Definition: poseupdate.h:62
hector_pose_estimation::PoseUpdate::max_angular_rate_xy_error_
double max_angular_rate_xy_error_
Definition: poseupdate.h:130
hector_pose_estimation::PoseUpdate::fixed_velocity_z_stddev_
double fixed_velocity_z_stddev_
Definition: poseupdate.h:120
hector_pose_estimation::YawModel::YawModel
YawModel()
Definition: poseupdate.h:64
hector_pose_estimation::PoseUpdate::max_velocity_xy_error_
double max_velocity_xy_error_
Definition: poseupdate.h:128
hector_pose_estimation::PositionZModel::~PositionZModel
virtual ~PositionZModel()
Definition: poseupdate.h:54
hector_pose_estimation::PoseUpdate::max_position_z_error_
double max_position_z_error_
Definition: poseupdate.h:125
hector_pose_estimation::PoseUpdate::fixed_position_z_stddev_
double fixed_position_z_stddev_
Definition: poseupdate.h:116
hector_pose_estimation::TwistModel::getExpectedValue
virtual void getExpectedValue(MeasurementVector &y_pred, const State &state)
Definition: poseupdate.cpp:496
hector_pose_estimation::PoseUpdate::updateImpl
virtual bool updateImpl(const MeasurementUpdate &update)
Definition: poseupdate.cpp:95
hector_pose_estimation::PoseUpdate::fixed_alpha_
double fixed_alpha_
Definition: poseupdate.h:109
hector_pose_estimation::PoseUpdate::position_xy_model_
PositionXYModel position_xy_model_
Definition: poseupdate.h:104


hector_pose_estimation_core
Author(s): Johannes Meyer
autogenerated on Wed Mar 2 2022 00:24:41