mars_lib 0.1.0.2abe2576fe7f
Modular and Robust Sensor-Fusion
Loading...
Searching...
No Matches
position_sensor_class.h
Go to the documentation of this file.
1// Copyright (C) 2021 Christian Brommer, Control of Networked Systems, University of Klagenfurt, Austria.
2//
3// All rights reserved.
4//
5// This software is licensed under the terms of the BSD-2-Clause-License with
6// no commercial use allowed, the full terms of which are made available
7// in the LICENSE file. No license in patents is granted.
8//
9// You can contact the author at <christian.brommer@ieee.org>
10
11#ifndef POSITIONSENSORCLASS_H
12#define POSITIONSENSORCLASS_H
13
14#include <mars/core_state.h>
15#include <mars/ekf.h>
20#include <mars/time.h>
22#include <iostream>
23#include <memory>
24#include <string>
25#include <utility>
26
27namespace mars
28{
30
32{
33public:
34 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
35
36 PositionSensorClass(const std::string& name, std::shared_ptr<CoreState> core_states)
37 {
38 name_ = name;
39 core_states_ = std::move(core_states);
40 const_ref_to_nav_ = false;
42
43 // chi2
44 chi2_.set_dof(3);
45
46 std::cout << "Created: [" << this->name_ << "] Sensor" << std::endl;
47 }
48
49 virtual ~PositionSensorClass() = default;
50
51 PositionSensorStateType get_state(const std::shared_ptr<void>& sensor_data)
52 {
53 PositionSensorData data = *static_cast<PositionSensorData*>(sensor_data.get());
54 return data.state_;
55 }
56
57 Eigen::MatrixXd get_covariance(const std::shared_ptr<void>& sensor_data)
58 {
59 PositionSensorData data = *static_cast<PositionSensorData*>(sensor_data.get());
60 return data.get_full_cov();
61 }
62
63 void set_initial_calib(std::shared_ptr<void> calibration)
64 {
65 initial_calib_ = calibration;
67 }
68
69 BufferDataType Initialize(const Time& timestamp, std::shared_ptr<void> /*sensor_data*/,
70 std::shared_ptr<CoreType> latest_core_data)
71 {
72 // PositionMeasurementType measurement = *static_cast<PositionMeasurementType*>(sensor_data.get());
73
74 PositionSensorData sensor_state;
75 std::string calibration_type;
76
78 {
79 calibration_type = "Given";
80
81 PositionSensorData calib = *static_cast<PositionSensorData*>(initial_calib_.get());
82
83 sensor_state.state_ = calib.state_;
84 sensor_state.sensor_cov_ = calib.sensor_cov_;
85 }
86 else
87 {
88 calibration_type = "Auto";
89 std::cout << "Position calibration AUTO init not implemented yet" << std::endl;
90 exit(EXIT_FAILURE);
91 }
92
93 // Bypass core state for the returned object
94 BufferDataType result(std::make_shared<CoreType>(*latest_core_data.get()),
95 std::make_shared<PositionSensorData>(sensor_state));
96
97 is_initialized_ = true;
98
99 std::cout << "Info: Initialized [" << name_ << "] with [" << calibration_type << "] Calibration at t=" << timestamp
100 << std::endl;
101
102 std::cout << "Info: [" << name_ << "] Calibration(rounded):" << std::endl;
103 std::cout << "\tPosition[m]: [" << sensor_state.state_.p_ip_.transpose() << " ]" << std::endl;
104
105 return result;
106 }
107
108 bool CalcUpdate(const Time& /*timestamp*/, std::shared_ptr<void> measurement, const CoreStateType& prior_core_state,
109 std::shared_ptr<void> latest_sensor_data, const Eigen::MatrixXd& prior_cov,
110 BufferDataType* new_state_data)
111 {
112 // Cast the sensor measurement and prior state information
113 PositionMeasurementType* meas = static_cast<PositionMeasurementType*>(measurement.get());
114 PositionSensorData* prior_sensor_data = static_cast<PositionSensorData*>(latest_sensor_data.get());
115
116 // Decompose sensor measurement
117 Eigen::Vector3d p_meas = meas->position_;
118
119 // Extract sensor state
120 PositionSensorStateType prior_sensor_state(prior_sensor_data->state_);
121
122 // Generate measurement noise matrix and check
123 // if noisevalues from the measurement object should be used
124 Eigen::MatrixXd R_meas_dyn;
126 {
127 meas->get_meas_noise(&R_meas_dyn);
128 }
129 else
130 {
131 R_meas_dyn = this->R_.asDiagonal();
132 }
133 const Eigen::Matrix<double, 3, 3> R_meas = R_meas_dyn;
134
135 const int size_of_core_state = CoreStateType::size_error_;
136 const int size_of_sensor_state = prior_sensor_state.cov_size_;
137 const int size_of_full_error_state = size_of_core_state + size_of_sensor_state;
138 const Eigen::MatrixXd P = prior_cov;
139 assert(P.size() == size_of_full_error_state * size_of_full_error_state);
140
141 // Calculate the measurement jacobian H
142 const Eigen::Matrix3d I_3 = Eigen::Matrix3d::Identity();
143 const Eigen::Vector3d P_wi = prior_core_state.p_wi_;
144 const Eigen::Matrix3d R_wi = prior_core_state.q_wi_.toRotationMatrix();
145 const Eigen::Vector3d P_ip = prior_sensor_state.p_ip_;
146
147 // Position
148 const Eigen::Matrix3d Hp_pwi = I_3;
149 const Eigen::Matrix3d Hp_vwi = Eigen::Matrix3d::Zero();
150 const Eigen::Matrix3d Hp_rwi = -R_wi * Utils::Skew(P_ip);
151 const Eigen::Matrix3d Hp_bw = Eigen::Matrix3d::Zero();
152 const Eigen::Matrix3d Hp_ba = Eigen::Matrix3d::Zero();
153 const Eigen::Matrix3d Hp_pip = R_wi;
154
155 // Assemble the jacobian for the position (horizontal)
156 // H_p = [Hp_pwi Hp_vwi Hp_rwi Hp_bw Hp_ba Hp_pig ];
157 Eigen::MatrixXd H(3, Hp_pwi.cols() + Hp_vwi.cols() + Hp_rwi.cols() + Hp_bw.cols() + Hp_ba.cols() + Hp_pip.cols());
158
159 H << Hp_pwi, Hp_vwi, Hp_rwi, Hp_bw, Hp_ba, Hp_pip;
160
161 // Calculate the residual z = z~ - (estimate)
162 // Position
163 const Eigen::Vector3d p_est = P_wi + R_wi * P_ip;
164 residual_ = Eigen::MatrixXd(p_est.rows(), 1);
165 residual_ = p_meas - p_est;
166
167 // Perform EKF calculations
168 mars::Ekf ekf(H, R_meas, residual_, P);
169 const Eigen::MatrixXd correction = ekf.CalculateCorrection(&chi2_);
170 assert(correction.size() == size_of_full_error_state * 1);
171
172 // Perform Chi2 test
173 if (!chi2_.passed_ && chi2_.do_test_)
174 {
176 return false;
177 }
178
179 Eigen::MatrixXd P_updated = ekf.CalculateCovUpdate();
180 assert(P_updated.size() == size_of_full_error_state * size_of_full_error_state);
181 P_updated = Utils::EnforceMatrixSymmetry(P_updated);
182
183 // Apply Core Correction
184 CoreStateVector core_correction = correction.block(0, 0, CoreStateType::size_error_, 1);
185 CoreStateType corrected_core_state = CoreStateType::ApplyCorrection(prior_core_state, core_correction);
186
187 // Apply Sensor Correction
188 const Eigen::MatrixXd sensor_correction = correction.block(size_of_core_state, 0, size_of_sensor_state, 1);
189 const PositionSensorStateType corrected_sensor_state = ApplyCorrection(prior_sensor_state, sensor_correction);
190
191 // Return Results
192 // CoreState data
193 CoreType core_data;
194 core_data.cov_ = P_updated.block(0, 0, CoreStateType::size_error_, CoreStateType::size_error_);
195 core_data.state_ = corrected_core_state;
196
197 // SensorState data
198 std::shared_ptr<PositionSensorData> sensor_data(std::make_shared<PositionSensorData>());
199 sensor_data->set_cov(P_updated);
200 sensor_data->state_ = corrected_sensor_state;
201
202 BufferDataType state_entry(std::make_shared<CoreType>(core_data), sensor_data);
203
205 {
206 // corrected_sensor_data.ref_to_nav = prior_ref_to_nav;
207 }
208 else
209 {
210 // TODO(chb) also estimate ref to nav
211 }
212
213 *new_state_data = state_entry;
214
215 return true;
216 }
217
219 const Eigen::MatrixXd& correction)
220 {
221 // state + error state correction
222
223 PositionSensorStateType corrected_sensor_state;
224 corrected_sensor_state.p_ip_ = prior_sensor_state.p_ip_ + correction.block(0, 0, 3, 1);
225 return corrected_sensor_state;
226 }
227};
228} // namespace mars
229
230#endif // POSITIONSENSORCLASS_H
bool has_meas_noise
Definition measurement_base_class.h:23
bool get_meas_noise(Eigen::MatrixXd *meas_noise)
get the measurement noise associated with the current sensor measurement
Definition measurement_base_class.h:25
int cov_size_
Definition base_states.h:25
The BaseSensorData class binds the sensor state and covariance matrix.
Definition bind_sensor_data.h:29
EIGEN_MAKE_ALIGNED_OPERATOR_NEW T state_
Definition bind_sensor_data.h:35
Eigen::MatrixXd get_full_cov() const
get_full_cov builds the full covariance matrix
Definition bind_sensor_data.h:63
Eigen::MatrixXd sensor_cov_
covariance of the sensor states
Definition bind_sensor_data.h:37
The BufferDataType binds the core and sensor state in form of a shared void pointer.
Definition buffer_data_type.h:36
bool passed_
Determine if the test is performed or not.
Definition ekf.h:84
bool do_test_
Upper critival value.
Definition ekf.h:83
void set_dof(const int &value)
set_dof Set degree of freedom for the X2 distribution
void PrintReport(const std::string &name)
PrintReport Print a formated report e.g. if the test did not pass.
Definition core_state_type.h:21
static constexpr int size_error_
Definition core_state_type.h:38
Eigen::Vector3d p_wi_
Definition core_state_type.h:27
Eigen::Quaternion< double > q_wi_
Definition core_state_type.h:29
static CoreStateType ApplyCorrection(CoreStateType state_prior, Eigen::Matrix< double, CoreStateType::size_error_, 1 > correction)
ApplyCorrection.
Definition core_state_type.h:46
Definition core_type.h:19
CoreStateMatrix cov_
Definition core_type.h:22
CoreStateType state_
Definition core_type.h:21
Definition ekf.h:92
Eigen::MatrixXd CalculateCovUpdate()
CalculateCovUpdate Updating the state covariance after the state update.
Eigen::MatrixXd CalculateCorrection()
Kalman gain.
Definition position_measurement_type.h:21
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d position_
Position [x y z].
Definition position_measurement_type.h:25
Definition position_sensor_class.h:32
PositionSensorStateType ApplyCorrection(const PositionSensorStateType &prior_sensor_state, const Eigen::MatrixXd &correction)
Definition position_sensor_class.h:218
void set_initial_calib(std::shared_ptr< void > calibration)
set_initial_calib Sets the calibration of an individual sensor
Definition position_sensor_class.h:63
Eigen::MatrixXd get_covariance(const std::shared_ptr< void > &sensor_data)
get_covariance Resolves a void pointer to the covariance matrix of the corresponding sensor type Each...
Definition position_sensor_class.h:57
PositionSensorStateType get_state(const std::shared_ptr< void > &sensor_data)
Definition position_sensor_class.h:51
bool CalcUpdate(const Time &, std::shared_ptr< void > measurement, const CoreStateType &prior_core_state, std::shared_ptr< void > latest_sensor_data, const Eigen::MatrixXd &prior_cov, BufferDataType *new_state_data)
CalcUpdate Calculates the update for an individual sensor definition.
Definition position_sensor_class.h:108
EIGEN_MAKE_ALIGNED_OPERATOR_NEW PositionSensorClass(const std::string &name, std::shared_ptr< CoreState > core_states)
Definition position_sensor_class.h:36
virtual ~PositionSensorClass()=default
BufferDataType Initialize(const Time &timestamp, std::shared_ptr< void >, std::shared_ptr< CoreType > latest_core_data)
Initialize the state of an individual sensor.
Definition position_sensor_class.h:69
Definition position_sensor_state_type.h:20
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d p_ip_
Definition position_sensor_state_type.h:24
std::string name_
Name of the individual sensor instance.
Definition sensor_abs_class.h:23
bool is_initialized_
True if the sensor has been initialized.
Definition sensor_abs_class.h:24
bool const_ref_to_nav_
True if the reference should not be estimated.
Definition sensor_abs_class.h:27
bool use_dynamic_meas_noise_
True if dynamic noise values from measurements should be used.
Definition sensor_abs_class.h:29
Definition time.h:20
Definition update_sensor_abs_class.h:24
bool initial_calib_provided_
True if an initial calibration was provided.
Definition update_sensor_abs_class.h:38
std::shared_ptr< CoreState > core_states_
Definition update_sensor_abs_class.h:42
Eigen::VectorXd R_
Measurement noise "squared".
Definition update_sensor_abs_class.h:32
std::shared_ptr< void > initial_calib_
Definition update_sensor_abs_class.h:37
Chi2 chi2_
Definition update_sensor_abs_class.h:40
Eigen::MatrixXd residual_
Definition update_sensor_abs_class.h:31
static Eigen::MatrixXd EnforceMatrixSymmetry(const Eigen::Ref< const Eigen::MatrixXd > &mat_in)
EnforceMatrixSymmetry.
static Eigen::Matrix3d Skew(const Eigen::Vector3d &v)
skew generate the skew symmetric matrix of v
Definition buffer.h:27
Eigen::Matrix< double, CoreStateType::size_error_, 1 > CoreStateVector
Definition core_state_type.h:135