sensor_fusion_ekf.cc 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336
  1. /*
  2. * Copyright 2019 Google Inc. All Rights Reserved.
  3. *
  4. * Licensed under the Apache License, Version 2.0 (the "License");
  5. * you may not use this file except in compliance with the License.
  6. * You may obtain a copy of the License at
  7. *
  8. * http://www.apache.org/licenses/LICENSE-2.0
  9. *
  10. * Unless required by applicable law or agreed to in writing, software
  11. * distributed under the License is distributed on an "AS IS" BASIS,
  12. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  13. * See the License for the specific language governing permissions and
  14. * limitations under the License.
  15. */
  16. #include "sensor_fusion_ekf.h"
  17. #include <algorithm>
  18. #include <cmath>
  19. #include "accelerometer_data.h"
  20. #include "gyroscope_data.h"
  21. #include "pose_prediction.h"
  22. #include "../util/matrixutils.h"
  23. namespace cardboard {
  24. namespace {
  25. const double kFiniteDifferencingEpsilon = 1.0e-7;
  26. const double kEpsilon = 1.0e-15;
  27. // Default gyroscope frequency. This corresponds to 100 Hz.
  28. const double kDefaultGyroscopeTimestep_s = 0.01f;
  29. // Maximum time between gyroscope before we start limiting the integration.
  30. const double kMaximumGyroscopeSampleDelay_s = 0.04f;
  31. // Compute a first-order exponential moving average of changes in accel norm per
  32. // frame.
  33. const double kSmoothingFactor = 0.5;
  34. // Minimum and maximum values used for accelerometer noise covariance matrix.
  35. // The smaller the sigma value, the more weight is given to the accelerometer
  36. // signal.
  37. const double kMinAccelNoiseSigma = 0.75;
  38. const double kMaxAccelNoiseSigma = 7.0;
  39. // Initial value for the diagonal elements of the different covariance matrices.
  40. const double kInitialStateCovarianceValue = 25.0;
  41. const double kInitialProcessCovarianceValue = 1.0;
  42. // Maximum accelerometer norm change allowed before capping it covariance to a
  43. // large value.
  44. const double kMaxAccelNormChange = 0.15;
  45. // Timestep IIR filtering coefficient.
  46. const double kTimestepFilterCoeff = 0.95;
  47. // Minimum number of sample for timestep filtering.
  48. const int kTimestepFilterMinSamples = 10;
  49. // Z direction in start space.
  50. const Vector3 kCanonicalZDirection(0.0, 0.0, 1.0);
  51. // Computes an axis-angle rotation from the input vector.
  52. // angle = norm(a)
  53. // axis = a.normalized()
  54. // If norm(a) == 0, it returns an identity rotation.
  55. static inline void RotationFromVector(const Vector3& a, Rotation& r)
  56. {
  57. const double norm_a = Length(a);
  58. if (norm_a < kEpsilon) {
  59. r = Rotation::Identity();
  60. return;
  61. }
  62. r = Rotation::FromAxisAndAngle(a / norm_a, norm_a);
  63. }
  64. } // namespace
  65. SensorFusionEkf::SensorFusionEkf()
  66. : execute_reset_with_next_accelerometer_sample_(false)
  67. , bias_estimation_enabled_(true)
  68. , gyroscope_bias_estimate_({ 0, 0, 0 })
  69. {
  70. ResetState();
  71. }
  72. void SensorFusionEkf::Reset() { execute_reset_with_next_accelerometer_sample_ = true; }
  73. void SensorFusionEkf::ResetState()
  74. {
  75. current_state_.sensor_from_start_rotation = Rotation::Identity();
  76. current_state_.sensor_from_start_rotation_velocity = Vector3::Zero();
  77. current_gyroscope_sensor_timestamp_ns_ = 0;
  78. current_accelerometer_sensor_timestamp_ns_ = 0;
  79. state_covariance_ = Matrix3x3::Identity() * kInitialStateCovarianceValue;
  80. process_covariance_ = Matrix3x3::Identity() * kInitialProcessCovarianceValue;
  81. accelerometer_measurement_covariance_
  82. = Matrix3x3::Identity() * kMinAccelNoiseSigma * kMinAccelNoiseSigma;
  83. innovation_covariance_ = Matrix3x3::Identity();
  84. accelerometer_measurement_jacobian_ = Matrix3x3::Zero();
  85. kalman_gain_ = Matrix3x3::Zero();
  86. innovation_ = Vector3::Zero();
  87. accelerometer_measurement_ = Vector3::Zero();
  88. prediction_ = Vector3::Zero();
  89. control_input_ = Vector3::Zero();
  90. state_update_ = Vector3::Zero();
  91. moving_average_accelerometer_norm_change_ = 0.0;
  92. is_timestep_filter_initialized_ = false;
  93. is_gyroscope_filter_valid_ = false;
  94. is_aligned_with_gravity_ = false;
  95. // Reset biases.
  96. gyroscope_bias_estimator_.Reset();
  97. gyroscope_bias_estimate_ = { 0, 0, 0 };
  98. }
  99. // Here I am doing something wrong relative to time stamps. The state timestamps
  100. // always correspond to the gyrostamps because it would require additional
  101. // extrapolation if I wanted to do otherwise.
  102. PoseState SensorFusionEkf::GetLatestPoseState() const { return current_state_; }
  103. void SensorFusionEkf::ProcessGyroscopeSample(const GyroscopeData& sample)
  104. {
  105. // Don't accept gyroscope sample when waiting for a reset.
  106. if (execute_reset_with_next_accelerometer_sample_) {
  107. return;
  108. }
  109. // Discard outdated samples.
  110. if (current_gyroscope_sensor_timestamp_ns_ >= sample.sensor_timestamp_ns) {
  111. current_gyroscope_sensor_timestamp_ns_ = sample.sensor_timestamp_ns;
  112. return;
  113. }
  114. // Checks that we received at least one gyroscope sample in the past.
  115. if (current_gyroscope_sensor_timestamp_ns_ != 0) {
  116. double current_timestep_s = std::chrono::duration_cast<std::chrono::duration<double>>(
  117. std::chrono::nanoseconds(
  118. sample.sensor_timestamp_ns - current_gyroscope_sensor_timestamp_ns_))
  119. .count();
  120. if (current_timestep_s > kMaximumGyroscopeSampleDelay_s) {
  121. if (is_gyroscope_filter_valid_) {
  122. // Replaces the delta timestamp by the filtered estimates of the delta time.
  123. current_timestep_s = filtered_gyroscope_timestep_s_;
  124. } else {
  125. current_timestep_s = kDefaultGyroscopeTimestep_s;
  126. }
  127. } else {
  128. FilterGyroscopeTimestep(current_timestep_s);
  129. }
  130. if (bias_estimation_enabled_) {
  131. gyroscope_bias_estimator_.ProcessGyroscope(sample.data, sample.sensor_timestamp_ns);
  132. if (gyroscope_bias_estimator_.IsCurrentEstimateValid()) {
  133. // As soon as the device is considered to be static, the bias estimator
  134. // should have a precise estimate of the gyroscope bias.
  135. gyroscope_bias_estimate_ = gyroscope_bias_estimator_.GetGyroscopeBias();
  136. }
  137. }
  138. // Only integrate after receiving an accelerometer sample.
  139. if (is_aligned_with_gravity_) {
  140. const Rotation rotation_from_gyroscope = pose_prediction::GetRotationFromGyroscope(
  141. { sample.data[0] - gyroscope_bias_estimate_[0],
  142. sample.data[1] - gyroscope_bias_estimate_[1],
  143. sample.data[2] - gyroscope_bias_estimate_[2] },
  144. current_timestep_s);
  145. current_state_.sensor_from_start_rotation
  146. = rotation_from_gyroscope * current_state_.sensor_from_start_rotation;
  147. UpdateStateCovariance(RotationMatrixNH(rotation_from_gyroscope));
  148. state_covariance_ = state_covariance_
  149. + ((current_timestep_s * current_timestep_s) * process_covariance_);
  150. }
  151. }
  152. // Saves gyroscope event for future prediction.
  153. current_state_.timestamp = sample.system_timestamp;
  154. current_gyroscope_sensor_timestamp_ns_ = sample.sensor_timestamp_ns;
  155. current_state_.sensor_from_start_rotation_velocity.Set(
  156. sample.data[0] - gyroscope_bias_estimate_[0], sample.data[1] - gyroscope_bias_estimate_[1],
  157. sample.data[2] - gyroscope_bias_estimate_[2]);
  158. }
  159. Vector3 SensorFusionEkf::ComputeInnovation(const Rotation& pose)
  160. {
  161. const Vector3 predicted_down_direction = pose * kCanonicalZDirection;
  162. const Rotation rotation
  163. = Rotation::RotateInto(predicted_down_direction, accelerometer_measurement_);
  164. Vector3 axis;
  165. double angle;
  166. rotation.GetAxisAndAngle(&axis, &angle);
  167. return axis * angle;
  168. }
  169. void SensorFusionEkf::ComputeMeasurementJacobian()
  170. {
  171. for (int dof = 0; dof < 3; dof++) {
  172. Vector3 delta = Vector3::Zero();
  173. delta[dof] = kFiniteDifferencingEpsilon;
  174. Rotation epsilon_rotation;
  175. RotationFromVector(delta, epsilon_rotation);
  176. const Vector3 delta_rotation
  177. = ComputeInnovation(epsilon_rotation * current_state_.sensor_from_start_rotation);
  178. const Vector3 col = (innovation_ - delta_rotation) / kFiniteDifferencingEpsilon;
  179. accelerometer_measurement_jacobian_(0, dof) = col[0];
  180. accelerometer_measurement_jacobian_(1, dof) = col[1];
  181. accelerometer_measurement_jacobian_(2, dof) = col[2];
  182. }
  183. }
  184. void SensorFusionEkf::ProcessAccelerometerSample(const AccelerometerData& sample)
  185. {
  186. // Discard outdated samples.
  187. if (current_accelerometer_sensor_timestamp_ns_ >= sample.sensor_timestamp_ns) {
  188. current_accelerometer_sensor_timestamp_ns_ = sample.sensor_timestamp_ns;
  189. return;
  190. }
  191. // Call reset state if required.
  192. if (execute_reset_with_next_accelerometer_sample_.exchange(false)) {
  193. ResetState();
  194. }
  195. accelerometer_measurement_.Set(sample.data[0], sample.data[1], sample.data[2]);
  196. current_accelerometer_sensor_timestamp_ns_ = sample.sensor_timestamp_ns;
  197. if (bias_estimation_enabled_) {
  198. gyroscope_bias_estimator_.ProcessAccelerometer(sample.data, sample.sensor_timestamp_ns);
  199. }
  200. if (!is_aligned_with_gravity_) {
  201. // This is the first accelerometer measurement so it initializes the
  202. // orientation estimate.
  203. current_state_.sensor_from_start_rotation
  204. = Rotation::RotateInto(kCanonicalZDirection, accelerometer_measurement_);
  205. is_aligned_with_gravity_ = true;
  206. previous_accelerometer_norm_ = Length(accelerometer_measurement_);
  207. return;
  208. }
  209. UpdateMeasurementCovariance();
  210. innovation_ = ComputeInnovation(current_state_.sensor_from_start_rotation);
  211. ComputeMeasurementJacobian();
  212. // S = H * P * H' + R
  213. innovation_covariance_ = accelerometer_measurement_jacobian_ * state_covariance_
  214. * Transpose(accelerometer_measurement_jacobian_)
  215. + accelerometer_measurement_covariance_;
  216. // K = P * H' * S^-1
  217. kalman_gain_ = state_covariance_ * Transpose(accelerometer_measurement_jacobian_)
  218. * Inverse(innovation_covariance_);
  219. // x_update = K*nu
  220. state_update_ = kalman_gain_ * innovation_;
  221. // P = (I - K * H) * P;
  222. state_covariance_ = (Matrix3x3::Identity() - kalman_gain_ * accelerometer_measurement_jacobian_)
  223. * state_covariance_;
  224. // Updates pose and associate covariance matrix.
  225. Rotation rotation_from_state_update;
  226. RotationFromVector(state_update_, rotation_from_state_update);
  227. current_state_.sensor_from_start_rotation
  228. = rotation_from_state_update * current_state_.sensor_from_start_rotation;
  229. UpdateStateCovariance(RotationMatrixNH(rotation_from_state_update));
  230. }
  231. void SensorFusionEkf::UpdateStateCovariance(const Matrix3x3& motion_update)
  232. {
  233. state_covariance_ = motion_update * state_covariance_ * Transpose(motion_update);
  234. }
  235. void SensorFusionEkf::FilterGyroscopeTimestep(double gyroscope_timestep_s)
  236. {
  237. if (!is_timestep_filter_initialized_) {
  238. // Initializes the filter.
  239. filtered_gyroscope_timestep_s_ = gyroscope_timestep_s;
  240. num_gyroscope_timestep_samples_ = 1;
  241. is_timestep_filter_initialized_ = true;
  242. return;
  243. }
  244. // Computes the IIR filter response.
  245. filtered_gyroscope_timestep_s_ = kTimestepFilterCoeff * filtered_gyroscope_timestep_s_
  246. + (1 - kTimestepFilterCoeff) * gyroscope_timestep_s;
  247. ++num_gyroscope_timestep_samples_;
  248. if (num_gyroscope_timestep_samples_ > kTimestepFilterMinSamples) {
  249. is_gyroscope_filter_valid_ = true;
  250. }
  251. }
  252. void SensorFusionEkf::UpdateMeasurementCovariance()
  253. {
  254. const double current_accelerometer_norm = Length(accelerometer_measurement_);
  255. // Norm change between current and previous accel readings.
  256. const double current_accelerometer_norm_change
  257. = std::abs(current_accelerometer_norm - previous_accelerometer_norm_);
  258. previous_accelerometer_norm_ = current_accelerometer_norm;
  259. moving_average_accelerometer_norm_change_ = kSmoothingFactor * current_accelerometer_norm_change
  260. + (1 - kSmoothingFactor) * moving_average_accelerometer_norm_change_;
  261. // If we hit the accel norm change threshold, we use the maximum noise sigma
  262. // for the accel covariance. For anything below that, we use a linear
  263. // combination between min and max sigma values.
  264. const double norm_change_ratio
  265. = moving_average_accelerometer_norm_change_ / kMaxAccelNormChange;
  266. const double accelerometer_noise_sigma = std::min(kMaxAccelNoiseSigma,
  267. kMinAccelNoiseSigma + norm_change_ratio * (kMaxAccelNoiseSigma - kMinAccelNoiseSigma));
  268. // Updates the accel covariance matrix with the new sigma value.
  269. accelerometer_measurement_covariance_
  270. = Matrix3x3::Identity() * accelerometer_noise_sigma * accelerometer_noise_sigma;
  271. }
  272. bool SensorFusionEkf::IsBiasEstimationEnabled() const { return bias_estimation_enabled_; }
  273. void SensorFusionEkf::SetBiasEstimationEnabled(bool enable)
  274. {
  275. if (bias_estimation_enabled_ != enable) {
  276. bias_estimation_enabled_ = enable;
  277. gyroscope_bias_estimate_ = { 0, 0, 0 };
  278. gyroscope_bias_estimator_.Reset();
  279. }
  280. }
  281. } // namespace cardboard