sensor_fusion_ekf.cc 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333
  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 Rotation RotationFromVector(const Vector3& a)
  56. {
  57. const double norm_a = Length(a);
  58. if (norm_a < kEpsilon) {
  59. return Rotation::Identity();
  60. }
  61. return Rotation::FromAxisAndAngle(a / norm_a, norm_a);
  62. }
  63. } // namespace
  64. SensorFusionEkf::SensorFusionEkf()
  65. : execute_reset_with_next_accelerometer_sample_(false)
  66. , bias_estimation_enabled_(true)
  67. , gyroscope_bias_estimate_({ 0, 0, 0 })
  68. {
  69. ResetState();
  70. }
  71. void SensorFusionEkf::Reset() { execute_reset_with_next_accelerometer_sample_ = true; }
  72. void SensorFusionEkf::ResetState()
  73. {
  74. current_state_.sensor_from_start_rotation = Rotation::Identity();
  75. current_state_.sensor_from_start_rotation_velocity = Vector3::Zero();
  76. current_gyroscope_sensor_timestamp_ns_ = 0;
  77. current_accelerometer_sensor_timestamp_ns_ = 0;
  78. state_covariance_ = Matrix3x3::Identity() * kInitialStateCovarianceValue;
  79. process_covariance_ = Matrix3x3::Identity() * kInitialProcessCovarianceValue;
  80. accelerometer_measurement_covariance_
  81. = Matrix3x3::Identity() * kMinAccelNoiseSigma * kMinAccelNoiseSigma;
  82. innovation_covariance_ = Matrix3x3::Identity();
  83. accelerometer_measurement_jacobian_ = Matrix3x3::Zero();
  84. kalman_gain_ = Matrix3x3::Zero();
  85. innovation_ = Vector3::Zero();
  86. accelerometer_measurement_ = Vector3::Zero();
  87. prediction_ = Vector3::Zero();
  88. control_input_ = Vector3::Zero();
  89. state_update_ = Vector3::Zero();
  90. moving_average_accelerometer_norm_change_ = 0.0;
  91. is_timestep_filter_initialized_ = false;
  92. is_gyroscope_filter_valid_ = false;
  93. is_aligned_with_gravity_ = false;
  94. // Reset biases.
  95. gyroscope_bias_estimator_.Reset();
  96. gyroscope_bias_estimate_ = { 0, 0, 0 };
  97. }
  98. // Here I am doing something wrong relative to time stamps. The state timestamps
  99. // always correspond to the gyrostamps because it would require additional
  100. // extrapolation if I wanted to do otherwise.
  101. PoseState SensorFusionEkf::GetLatestPoseState() const { return current_state_; }
  102. void SensorFusionEkf::ProcessGyroscopeSample(const GyroscopeData& sample)
  103. {
  104. // Don't accept gyroscope sample when waiting for a reset.
  105. if (execute_reset_with_next_accelerometer_sample_) {
  106. return;
  107. }
  108. // Discard outdated samples.
  109. if (current_gyroscope_sensor_timestamp_ns_ >= sample.sensor_timestamp_ns) {
  110. current_gyroscope_sensor_timestamp_ns_ = sample.sensor_timestamp_ns;
  111. return;
  112. }
  113. // Checks that we received at least one gyroscope sample in the past.
  114. if (current_gyroscope_sensor_timestamp_ns_ != 0) {
  115. double current_timestep_s = std::chrono::duration_cast<std::chrono::duration<double>>(
  116. std::chrono::nanoseconds(
  117. sample.sensor_timestamp_ns - current_gyroscope_sensor_timestamp_ns_))
  118. .count();
  119. if (current_timestep_s > kMaximumGyroscopeSampleDelay_s) {
  120. if (is_gyroscope_filter_valid_) {
  121. // Replaces the delta timestamp by the filtered estimates of the delta time.
  122. current_timestep_s = filtered_gyroscope_timestep_s_;
  123. } else {
  124. current_timestep_s = kDefaultGyroscopeTimestep_s;
  125. }
  126. } else {
  127. FilterGyroscopeTimestep(current_timestep_s);
  128. }
  129. if (bias_estimation_enabled_) {
  130. gyroscope_bias_estimator_.ProcessGyroscope(sample.data, sample.sensor_timestamp_ns);
  131. if (gyroscope_bias_estimator_.IsCurrentEstimateValid()) {
  132. // As soon as the device is considered to be static, the bias estimator
  133. // should have a precise estimate of the gyroscope bias.
  134. gyroscope_bias_estimate_ = gyroscope_bias_estimator_.GetGyroscopeBias();
  135. }
  136. }
  137. // Only integrate after receiving an accelerometer sample.
  138. if (is_aligned_with_gravity_) {
  139. const Rotation rotation_from_gyroscope = pose_prediction::GetRotationFromGyroscope(
  140. { sample.data[0] - gyroscope_bias_estimate_[0],
  141. sample.data[1] - gyroscope_bias_estimate_[1],
  142. sample.data[2] - gyroscope_bias_estimate_[2] },
  143. current_timestep_s);
  144. current_state_.sensor_from_start_rotation
  145. = rotation_from_gyroscope * current_state_.sensor_from_start_rotation;
  146. UpdateStateCovariance(RotationMatrixNH(rotation_from_gyroscope));
  147. state_covariance_ = state_covariance_
  148. + ((current_timestep_s * current_timestep_s) * process_covariance_);
  149. }
  150. }
  151. // Saves gyroscope event for future prediction.
  152. current_state_.timestamp = sample.system_timestamp;
  153. current_gyroscope_sensor_timestamp_ns_ = sample.sensor_timestamp_ns;
  154. current_state_.sensor_from_start_rotation_velocity.Set(
  155. sample.data[0] - gyroscope_bias_estimate_[0], sample.data[1] - gyroscope_bias_estimate_[1],
  156. sample.data[2] - gyroscope_bias_estimate_[2]);
  157. }
  158. Vector3 SensorFusionEkf::ComputeInnovation(const Rotation& pose)
  159. {
  160. const Vector3 predicted_down_direction = pose * kCanonicalZDirection;
  161. const Rotation rotation
  162. = Rotation::RotateInto(predicted_down_direction, accelerometer_measurement_);
  163. Vector3 axis;
  164. double angle;
  165. rotation.GetAxisAndAngle(&axis, &angle);
  166. return axis * angle;
  167. }
  168. void SensorFusionEkf::ComputeMeasurementJacobian()
  169. {
  170. for (int dof = 0; dof < 3; dof++) {
  171. Vector3 delta = Vector3::Zero();
  172. delta[dof] = kFiniteDifferencingEpsilon;
  173. const Rotation epsilon_rotation = RotationFromVector(delta);
  174. const Vector3 delta_rotation
  175. = ComputeInnovation(epsilon_rotation * current_state_.sensor_from_start_rotation);
  176. const Vector3 col = (innovation_ - delta_rotation) / kFiniteDifferencingEpsilon;
  177. accelerometer_measurement_jacobian_(0, dof) = col[0];
  178. accelerometer_measurement_jacobian_(1, dof) = col[1];
  179. accelerometer_measurement_jacobian_(2, dof) = col[2];
  180. }
  181. }
  182. void SensorFusionEkf::ProcessAccelerometerSample(const AccelerometerData& sample)
  183. {
  184. // Discard outdated samples.
  185. if (current_accelerometer_sensor_timestamp_ns_ >= sample.sensor_timestamp_ns) {
  186. current_accelerometer_sensor_timestamp_ns_ = sample.sensor_timestamp_ns;
  187. return;
  188. }
  189. // Call reset state if required.
  190. if (execute_reset_with_next_accelerometer_sample_.exchange(false)) {
  191. ResetState();
  192. }
  193. accelerometer_measurement_.Set(sample.data[0], sample.data[1], sample.data[2]);
  194. current_accelerometer_sensor_timestamp_ns_ = sample.sensor_timestamp_ns;
  195. if (bias_estimation_enabled_) {
  196. gyroscope_bias_estimator_.ProcessAccelerometer(sample.data, sample.sensor_timestamp_ns);
  197. }
  198. if (!is_aligned_with_gravity_) {
  199. // This is the first accelerometer measurement so it initializes the
  200. // orientation estimate.
  201. current_state_.sensor_from_start_rotation
  202. = Rotation::RotateInto(kCanonicalZDirection, accelerometer_measurement_);
  203. is_aligned_with_gravity_ = true;
  204. previous_accelerometer_norm_ = Length(accelerometer_measurement_);
  205. return;
  206. }
  207. UpdateMeasurementCovariance();
  208. innovation_ = ComputeInnovation(current_state_.sensor_from_start_rotation);
  209. ComputeMeasurementJacobian();
  210. // S = H * P * H' + R
  211. innovation_covariance_ = accelerometer_measurement_jacobian_ * state_covariance_
  212. * Transpose(accelerometer_measurement_jacobian_)
  213. + accelerometer_measurement_covariance_;
  214. // K = P * H' * S^-1
  215. kalman_gain_ = state_covariance_ * Transpose(accelerometer_measurement_jacobian_)
  216. * Inverse(innovation_covariance_);
  217. // x_update = K*nu
  218. state_update_ = kalman_gain_ * innovation_;
  219. // P = (I - K * H) * P;
  220. state_covariance_ = (Matrix3x3::Identity() - kalman_gain_ * accelerometer_measurement_jacobian_)
  221. * state_covariance_;
  222. // Updates pose and associate covariance matrix.
  223. const Rotation rotation_from_state_update = RotationFromVector(state_update_);
  224. current_state_.sensor_from_start_rotation
  225. = rotation_from_state_update * current_state_.sensor_from_start_rotation;
  226. UpdateStateCovariance(RotationMatrixNH(rotation_from_state_update));
  227. }
  228. void SensorFusionEkf::UpdateStateCovariance(const Matrix3x3& motion_update)
  229. {
  230. state_covariance_ = motion_update * state_covariance_ * Transpose(motion_update);
  231. }
  232. void SensorFusionEkf::FilterGyroscopeTimestep(double gyroscope_timestep_s)
  233. {
  234. if (!is_timestep_filter_initialized_) {
  235. // Initializes the filter.
  236. filtered_gyroscope_timestep_s_ = gyroscope_timestep_s;
  237. num_gyroscope_timestep_samples_ = 1;
  238. is_timestep_filter_initialized_ = true;
  239. return;
  240. }
  241. // Computes the IIR filter response.
  242. filtered_gyroscope_timestep_s_ = kTimestepFilterCoeff * filtered_gyroscope_timestep_s_
  243. + (1 - kTimestepFilterCoeff) * gyroscope_timestep_s;
  244. ++num_gyroscope_timestep_samples_;
  245. if (num_gyroscope_timestep_samples_ > kTimestepFilterMinSamples) {
  246. is_gyroscope_filter_valid_ = true;
  247. }
  248. }
  249. void SensorFusionEkf::UpdateMeasurementCovariance()
  250. {
  251. const double current_accelerometer_norm = Length(accelerometer_measurement_);
  252. // Norm change between current and previous accel readings.
  253. const double current_accelerometer_norm_change
  254. = std::abs(current_accelerometer_norm - previous_accelerometer_norm_);
  255. previous_accelerometer_norm_ = current_accelerometer_norm;
  256. moving_average_accelerometer_norm_change_ = kSmoothingFactor * current_accelerometer_norm_change
  257. + (1 - kSmoothingFactor) * moving_average_accelerometer_norm_change_;
  258. // If we hit the accel norm change threshold, we use the maximum noise sigma
  259. // for the accel covariance. For anything below that, we use a linear
  260. // combination between min and max sigma values.
  261. const double norm_change_ratio
  262. = moving_average_accelerometer_norm_change_ / kMaxAccelNormChange;
  263. const double accelerometer_noise_sigma = std::min(kMaxAccelNoiseSigma,
  264. kMinAccelNoiseSigma + norm_change_ratio * (kMaxAccelNoiseSigma - kMinAccelNoiseSigma));
  265. // Updates the accel covariance matrix with the new sigma value.
  266. accelerometer_measurement_covariance_
  267. = Matrix3x3::Identity() * accelerometer_noise_sigma * accelerometer_noise_sigma;
  268. }
  269. bool SensorFusionEkf::IsBiasEstimationEnabled() const { return bias_estimation_enabled_; }
  270. void SensorFusionEkf::SetBiasEstimationEnabled(bool enable)
  271. {
  272. if (bias_estimation_enabled_ != enable) {
  273. bias_estimation_enabled_ = enable;
  274. gyroscope_bias_estimate_ = { 0, 0, 0 };
  275. gyroscope_bias_estimator_.Reset();
  276. }
  277. }
  278. } // namespace cardboard