footPDR.c 20 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846
  1. #include "pdrStatus.h"
  2. #include "footPDR.h"
  3. #include "system.h"
  4. #define GYR_BUFF_SIZE 3
  5. //当地的重力加速度
  6. float g = 9.8179995f;
  7. float dt = 0.01f;
  8. float P[81], acc_n[3];
  9. float Temporary_array1[9], Temporary_array2[9];
  10. float K[27], P_prev[81], delta_x[9];
  11. float C[9], C_prev[9];
  12. float vel_n[3], pos_n[3];
  13. float last_pos_n[3];
  14. float pos_offset[3];
  15. int stand_num = 0;
  16. float gyr_extreme[6];
  17. float gyr_mean[3];
  18. float num_peak;
  19. float gyrBias[3];
  20. uint32_t frame_index = 0;
  21. //重置磁航向,计算双脚的磁航向,以确定身体的正朝向
  22. float heading_buff[20];
  23. float zupt_heading;
  24. int step_index = 0;
  25. int32_t last_timestamp;
  26. //速度均值
  27. float vel_sum;
  28. int dt_sum;
  29. float vel_mean;
  30. //计算触地持续采样点
  31. int zupt_count;
  32. void set_pdr_status()
  33. {
  34. frame_index = 0;
  35. }
  36. void calVelMean(int zupt)
  37. {
  38. vel_mean = sqrt(vel_n[0] * vel_n[0] + vel_n[1] * vel_n[1] + vel_n[2] * vel_n[2]);
  39. }
  40. float getVelMean()
  41. {
  42. return vel_mean;
  43. }
  44. void saveStepData(int index, float heading)
  45. {
  46. heading_buff[index % 20] = heading;
  47. }
  48. float calDeltaHeading(int index, float now_heading)
  49. {
  50. //寻找相似的方向
  51. int start_index = index - 20;
  52. if(start_index < 0)
  53. start_index = 0;
  54. float deltaHeading;
  55. for(int i = start_index; i < index; i++)
  56. {
  57. deltaHeading = now_heading - heading_buff[i % 20];
  58. if(deltaHeading < -3.141591f)
  59. {
  60. deltaHeading = (deltaHeading + 6.2831852f);
  61. }
  62. else if(deltaHeading > 3.141591f)
  63. {
  64. deltaHeading = (deltaHeading - 6.2831852f);
  65. }
  66. if(fabsf(deltaHeading) < 0.0873f)//5/180*pi
  67. {
  68. return deltaHeading;
  69. }
  70. }
  71. return 99;
  72. }
  73. void calKafmanGain9x4(float *K, float *P)
  74. {
  75. float m_rever[4][4];
  76. float m[4][4];
  77. m[0][0] = P[20];m[0][1] = P[24];m[0][2] = P[25];m[0][3] = P[26];
  78. m[1][0] = P[56];m[1][1] = P[60];m[1][2] = P[61];m[1][3] = P[62];
  79. m[2][0] = P[65];m[2][1] = P[69];m[2][2] = P[70];m[2][3] = P[71];
  80. m[3][0] = P[74];m[3][1] = P[78];m[3][2] = P[79];m[3][3] = P[80];
  81. for(int i = 0; i < 4; i++)
  82. {
  83. m[i][i] += SIGMA_V * SIGMA_V;
  84. }
  85. //m[3][3] += 0.01f*0.01f;
  86. matrix_inverse(m, m_rever);
  87. K[0] = P[2] * m_rever[0][0] + P[6] * m_rever[1][0] + P[7] * m_rever[2][0] + P[8] * m_rever[3][0];
  88. K[1] = P[2] * m_rever[0][1] + P[6] * m_rever[1][1] + P[7] * m_rever[2][1] + P[8] * m_rever[3][1];
  89. K[2] = P[2] * m_rever[0][2] + P[6] * m_rever[1][2] + P[7] * m_rever[2][2] + P[8] * m_rever[3][2];
  90. K[3] = P[2] * m_rever[0][3] + P[6] * m_rever[1][3] + P[7] * m_rever[2][3] + P[8] * m_rever[3][3];
  91. K[4] = P[11] * m_rever[0][0] + P[15] * m_rever[1][0] + P[16] * m_rever[2][0] + P[17] * m_rever[3][0];
  92. K[5] = P[11] * m_rever[0][1] + P[15] * m_rever[1][1] + P[16] * m_rever[2][1] + P[17] * m_rever[3][1];
  93. K[6] = P[11] * m_rever[0][2] + P[15] * m_rever[1][2] + P[16] * m_rever[2][2] + P[17] * m_rever[3][2];
  94. K[7] = P[11] * m_rever[0][3] + P[15] * m_rever[1][3] + P[16] * m_rever[2][3] + P[17] * m_rever[3][3];
  95. K[8] = P[20] * m_rever[0][0] + P[24] * m_rever[1][0] + P[25] * m_rever[2][0] + P[26] * m_rever[3][0];
  96. K[9] = P[20] * m_rever[0][1] + P[24] * m_rever[1][1] + P[25] * m_rever[2][1] + P[26] * m_rever[3][1];
  97. K[10] = P[20] * m_rever[0][2] + P[24] * m_rever[1][2] + P[25] * m_rever[2][2] + P[26] * m_rever[3][2];
  98. K[11] = P[20] * m_rever[0][3] + P[24] * m_rever[1][3] + P[25] * m_rever[2][3] + P[26] * m_rever[3][3];
  99. K[12] = P[29] * m_rever[0][0] + P[33] * m_rever[1][0] + P[34] * m_rever[2][0] + P[35] * m_rever[3][0];
  100. K[13] = P[29] * m_rever[0][1] + P[33] * m_rever[1][1] + P[34] * m_rever[2][1] + P[35] * m_rever[3][1];
  101. K[14] = P[29] * m_rever[0][2] + P[33] * m_rever[1][2] + P[34] * m_rever[2][2] + P[35] * m_rever[3][2];
  102. K[15] = P[29] * m_rever[0][3] + P[33] * m_rever[1][3] + P[34] * m_rever[2][3] + P[35] * m_rever[3][3];
  103. K[16] = P[38] * m_rever[0][0] + P[42] * m_rever[1][0] + P[43] * m_rever[2][0] + P[44] * m_rever[3][0];
  104. K[17] = P[38] * m_rever[0][1] + P[42] * m_rever[1][1] + P[43] * m_rever[2][1] + P[44] * m_rever[3][1];
  105. K[18] = P[38] * m_rever[0][2] + P[42] * m_rever[1][2] + P[43] * m_rever[2][2] + P[44] * m_rever[3][2];
  106. K[19] = P[38] * m_rever[0][3] + P[42] * m_rever[1][3] + P[43] * m_rever[2][3] + P[44] * m_rever[3][3];
  107. K[20] = P[47] * m_rever[0][0] + P[51] * m_rever[1][0] + P[52] * m_rever[2][0] + P[53] * m_rever[3][0];
  108. K[21] = P[47] * m_rever[0][1] + P[51] * m_rever[1][1] + P[52] * m_rever[2][1] + P[53] * m_rever[3][1];
  109. K[22] = P[47] * m_rever[0][2] + P[51] * m_rever[1][2] + P[52] * m_rever[2][2] + P[53] * m_rever[3][2];
  110. K[23] = P[47] * m_rever[0][3] + P[51] * m_rever[1][3] + P[52] * m_rever[2][3] + P[53] * m_rever[3][3];
  111. K[24] = P[56] * m_rever[0][0] + P[60] * m_rever[1][0] + P[61] * m_rever[2][0] + P[62] * m_rever[3][0];
  112. K[25] = P[56] * m_rever[0][1] + P[60] * m_rever[1][1] + P[61] * m_rever[2][1] + P[62] * m_rever[3][1];
  113. K[26] = P[56] * m_rever[0][2] + P[60] * m_rever[1][2] + P[61] * m_rever[2][2] + P[62] * m_rever[3][2];
  114. K[27] = P[56] * m_rever[0][3] + P[60] * m_rever[1][3] + P[61] * m_rever[2][3] + P[62] * m_rever[3][3];
  115. K[28] = P[65] * m_rever[0][0] + P[69] * m_rever[1][0] + P[70] * m_rever[2][0] + P[71] * m_rever[3][0];
  116. K[29] = P[65] * m_rever[0][1] + P[69] * m_rever[1][1] + P[70] * m_rever[2][1] + P[71] * m_rever[3][1];
  117. K[30] = P[65] * m_rever[0][2] + P[69] * m_rever[1][2] + P[70] * m_rever[2][2] + P[71] * m_rever[3][2];
  118. K[31] = P[65] * m_rever[0][3] + P[69] * m_rever[1][3] + P[70] * m_rever[2][3] + P[71] * m_rever[3][3];
  119. K[32] = P[74] * m_rever[0][0] + P[78] * m_rever[1][0] + P[79] * m_rever[2][0] + P[80] * m_rever[3][0];
  120. K[33] = P[74] * m_rever[0][1] + P[78] * m_rever[1][1] + P[79] * m_rever[2][1] + P[80] * m_rever[3][1];
  121. K[34] = P[74] * m_rever[0][2] + P[78] * m_rever[1][2] + P[79] * m_rever[2][2] + P[80] * m_rever[3][2];
  122. K[35] = P[74] * m_rever[0][3] + P[78] * m_rever[1][3] + P[79] * m_rever[2][3] + P[80] * m_rever[3][3];
  123. }
  124. void calDeltaX9x4(float *K, float *measure, float *delta_x)
  125. {
  126. for(int i = 0; i < 9; i++)
  127. {
  128. delta_x[i] = 0.0f;
  129. for(int j = 0; j < 4; j ++)
  130. {
  131. delta_x[i] += (K[i * 4 + j] *measure[j]);
  132. }
  133. }
  134. }
  135. void calStateCov9x4(float *P, float *K)
  136. {
  137. static float P_copy[81];
  138. for(int i = 0; i < 9; i++)
  139. {
  140. for(int j = 0; j < 9; j++)
  141. {
  142. P_copy[i * 9 + j] = K[i * 4] * P[18 + j] + K[i * 4 + 1] * P[54 + j] + K[i * 4 + 2] * P[63 + j] + K[i * 4 + 3] * P[72 + j];
  143. }
  144. }
  145. for(int i = 0; i < 81 ; i ++)
  146. {
  147. P[i] -= P_copy[i];
  148. }
  149. }
  150. float calHeading(float mag[3], float acc[3])
  151. {
  152. float hSqrt;
  153. float eSqrt;
  154. float h[3]; //东向
  155. h[0] = mag[1] * acc[2] - mag[2] * acc[1];
  156. h[1] = mag[2] * acc[0] - mag[0] * acc[2];
  157. h[2] = mag[0] * acc[1] - mag[1] * acc[0];
  158. hSqrt = 1/sqrt(h[0] * h[0] + h[1] * h[1] + h[2] * h[2]);
  159. for(int i = 0; i < 3; i++)
  160. {
  161. h[i] *= hSqrt;
  162. }
  163. float e[3]; //北向
  164. e[0] = acc[1] * h[2] - acc[2] * h[1];
  165. e[1] = acc[2] * h[0] - acc[0] * h[2];
  166. e[2] = acc[0] * h[1] - acc[1] * h[0];
  167. eSqrt = 1/sqrt(e[0] * e[0] + e[1] * e[1] + e[2] * e[2]);
  168. for(int i = 0; i < 3; i++)
  169. {
  170. e[i] *= eSqrt;
  171. }
  172. return atan2(-h[1], e[1]);
  173. }
  174. void resetAttbyMag(float C[9], float acc[3], float mag[3])
  175. {
  176. float accScale = sqrt(acc[0] * acc[0] + acc[1] * acc[1] + acc[2] * acc[2]);
  177. float pitch = asin(-acc[0]/accScale);
  178. float roll = atan2(acc[1], acc[2]);
  179. float pitch_sin = sin(pitch);
  180. float pitch_cos = cos(pitch);
  181. float roll_sin = sin(roll);
  182. float roll_cos = cos(roll);
  183. float mag_heading;
  184. C[0] = pitch_cos;
  185. C[1] = pitch_sin * roll_sin;
  186. C[2] = pitch_sin * roll_cos;
  187. C[3] = 0.0;
  188. C[4] = roll_cos;
  189. C[5] = -roll_sin;
  190. mag_heading = atan2(-C[4] * mag[1] - C[5] * mag[2], C[0] * mag[0] + C[1] * mag[1] + C[2] * mag[2]);
  191. float yaw_sin = sin(mag_heading);
  192. float yaw_cos = cos(mag_heading);
  193. C[0] = pitch_cos * yaw_cos;
  194. C[1] = pitch_sin * roll_sin * yaw_cos - roll_cos * yaw_sin;
  195. C[2] = pitch_sin * roll_cos * yaw_cos + roll_sin * yaw_sin;
  196. C[3] = pitch_cos * yaw_sin;
  197. C[4] = pitch_sin * roll_sin * yaw_sin + roll_cos * yaw_cos;
  198. C[5] = pitch_sin * roll_cos * yaw_sin - roll_sin * yaw_cos;
  199. C[6] = acc[0];
  200. C[7] = acc[1];
  201. C[8] = acc[2];
  202. }
  203. void Initialize(float *gyr, float *acc)
  204. {
  205. stand_num = 0;
  206. memset(last_pos_n, 0, 3 * sizeof(float));
  207. memset(pos_offset, 0, 3 * sizeof(float));
  208. memset(P, 0, 81 * sizeof(float));
  209. memset(acc_n, 0, 3 * sizeof(float));
  210. memset(vel_n, 0, 3 * sizeof(float));
  211. memset(pos_n, 0, 3 * sizeof(float));
  212. memset(Temporary_array1, 0, 9 * sizeof(float));
  213. memset(Temporary_array2, 0, 9 * sizeof(float));
  214. memset(K, 0, 27 * sizeof(float));
  215. memset(P_prev, 0, 81 * sizeof(float));
  216. memset(delta_x, 0, 9 * sizeof(float));
  217. memset(C, 0, 9 * sizeof(float));
  218. memset(Temporary_array1, 0, 9 * sizeof(float));
  219. memset(Temporary_array2, 0, 9 * sizeof(float));
  220. init_attitude_matrix(C, acc, g);
  221. memcpy(C_prev, C, 9 * sizeof(float));
  222. zupt_count = 0;
  223. // memcpy(gyrBias, (uint32_t *)FLASH_ADD, 3 * sizeof(float));
  224. }
  225. void attitude_matrix_update(float *C, float *Temporary_array1, float *Temporary_array2, float *gyr, float dt)
  226. {
  227. Temporary_array1[0] = 2.0f;
  228. Temporary_array1[1] = dt * gyr[2];
  229. Temporary_array1[2] = -dt * gyr[1];
  230. Temporary_array1[3] = -dt * gyr[2];
  231. Temporary_array1[4] = 2.0f;
  232. Temporary_array1[5] = dt * gyr[0];
  233. Temporary_array1[6] = dt * gyr[1];
  234. Temporary_array1[7] = -dt * gyr[0];
  235. Temporary_array1[8] = 2.0f;
  236. invert3x3(Temporary_array1, Temporary_array2);
  237. memset(Temporary_array1, 0, 9 * sizeof(float));
  238. Temporary_array1[0] = 2 * C[0] + C[1] * dt * gyr[2] - C[2] * dt * gyr[1];
  239. Temporary_array1[1] = 2 * C[1] - C[0] * dt * gyr[2] + C[2] * dt * gyr[0];
  240. Temporary_array1[2] = 2 * C[2] + C[0] * dt * gyr[1] - C[1] * dt * gyr[0];
  241. Temporary_array1[3] = 2 * C[3] + C[4] * dt * gyr[2] - C[5] * dt * gyr[1];
  242. Temporary_array1[4] = 2 * C[4] - C[3] * dt * gyr[2] + C[5] * dt * gyr[0];
  243. Temporary_array1[5] = 2 * C[5] + C[3] * dt * gyr[1] - C[4] * dt * gyr[0];
  244. Temporary_array1[6] = 2 * C[6] + C[7] * dt * gyr[2] - C[8] * dt * gyr[1];
  245. Temporary_array1[7] = 2 * C[7] - C[6] * dt * gyr[2] + C[8] * dt * gyr[0];
  246. Temporary_array1[8] = 2 * C[8] + C[6] * dt * gyr[1] - C[7] * dt * gyr[0];
  247. multiply3x3(Temporary_array1, Temporary_array2, C);
  248. }
  249. float max_window_val(float *window, int window_size)
  250. {
  251. float val = window[0];
  252. for (int i = 0; i < window_size; i++)
  253. {
  254. if (window[i] > val)
  255. val = window[i];
  256. }
  257. return val;
  258. }
  259. int max_window_int(int *window, int window_size)
  260. {
  261. int val = window[0];
  262. for (int i = 0; i < window_size; i++)
  263. {
  264. if (window[i] > val)
  265. val = window[i];
  266. }
  267. return val;
  268. }
  269. float min_window_val(float *window, int window_size)
  270. {
  271. float val = window[0];
  272. for (int i = 0; i < window_size; i++)
  273. {
  274. if (window[i] < val)
  275. val = window[i];
  276. }
  277. return val;
  278. }
  279. int min_window_int(int *window, int window_size)
  280. {
  281. int val = window[0];
  282. for (int i = 0; i < window_size; i++)
  283. {
  284. if (window[i] < val)
  285. val = window[i];
  286. }
  287. return val;
  288. }
  289. //press_tren 函数功能:提供走路过程中上升沿,下降沿
  290. //1 为上升 2 为 下降 0为不需要得状态
  291. int press_trend(int index, int *window, int window_size)
  292. {
  293. int i;
  294. int max_val = window[(index - 1) % window_size];
  295. int max_index = index;
  296. int min_val = max_val;
  297. int min_index = max_index;
  298. for (i = 1; i < window_size + 1; i++)
  299. {
  300. if (max_val < window[(index - i) % window_size])
  301. {
  302. max_index = index - i + 1;
  303. max_val = window[(index - i) % window_size];
  304. }
  305. if (min_val > window[(index - i) % window_size])
  306. {
  307. min_index = index - i + 1;
  308. min_val = window[(index - i) % window_size];
  309. }
  310. }
  311. if (max_index > min_index && max_val > min_val + 50000)
  312. {
  313. return 1;
  314. }
  315. if (max_index < min_index && max_val > min_val + 50000)
  316. {
  317. return 2;
  318. }
  319. return 0;
  320. }
  321. void dcm2angle(float *dcm, float *roll, float *pitch, float *yaw)
  322. {
  323. *yaw = atan2(dcm[3], dcm[0]);
  324. *pitch = asin(-dcm[6]);
  325. *roll = atan2(dcm[7], dcm[8]);
  326. }
  327. void quat2angleTest(float qin[4], float *roll, float *pitch, float *yaw)
  328. {
  329. //float r11 = qin[0] * qin[0] + qin[1] * qin[1] - qin[2] * qin[2] - qin[3] * qin[3];
  330. float r11 = 2.0f * (qin[1] * qin[2] + qin[0] * qin[3]);
  331. //float r21 = 2.0f * (qin[1] * qin[2] - qin[0] * qin[3]);
  332. float r12 = qin[0] * qin[0] + qin[1] * qin[1] - qin[2] * qin[2] - qin[3] * qin[3];
  333. float r21 = -2.0f * (qin[1] * qin[3] - qin[0] * qin[2]);
  334. float r31 = 2.0f * (qin[2] * qin[3] + qin[0] * qin[1]);
  335. float r32 = qin[0] * qin[0] - qin[1] * qin[1] - qin[2] * qin[2] + qin[3] * qin[3];
  336. if (r21 < -0.999999999f)
  337. r21 = -1.0f;
  338. else if (r21 > 0.999999999f)
  339. r21 = 1.0f;
  340. *roll = atan2(r11, r12);
  341. *pitch = asin(r21);
  342. *yaw = atan2(r31, r32);
  343. }
  344. void dcm2angleTest(float C[9], short att[3])
  345. {
  346. float yaw, pitch, roll;
  347. pitch = asin(-C[6]);
  348. if(C[6] > 0.999999f || C[6] < -0.999999f)
  349. {
  350. //当俯仰角为90度的时候,则假设翻滚角为0度
  351. yaw = atan2(-C[1], C[4]);
  352. roll = 0.0f;
  353. }
  354. else
  355. {
  356. yaw = atan2(C[3], C[0]);
  357. roll = atan2(C[7], C[8]);
  358. }
  359. att[0] = (short)(yaw * 10000.f); //yaw
  360. att[1] = (short)(pitch * 10000.f); //pitch
  361. att[2] = (short)(roll * 10000.f); //roll
  362. }
  363. void quat2dcm(float *qin, float *dcm)
  364. {
  365. float qin_norm = 1 / sqrt(qin[0] * qin[0] + qin[1] * qin[1] + qin[2] * qin[2] + qin[3] * qin[3]);
  366. for (int i = 0; i < 4; i++)
  367. qin[i] *= qin_norm;
  368. dcm[0] = qin[0] * qin[0] + qin[1] * qin[1] - qin[2] * qin[2] - qin[3] * qin[3];
  369. dcm[1] = 2.0f * (qin[1] * qin[2] + qin[0] * qin[3]);
  370. dcm[2] = 2.0f * (qin[1] * qin[3] - qin[0] * qin[2]);
  371. dcm[3] = 2.0f * (qin[1] * qin[2] - qin[0] * qin[3]);
  372. dcm[4] = qin[0] * qin[0] - qin[1] * qin[1] + qin[2] * qin[2] - qin[3] * qin[3];
  373. dcm[5] = 2.0f * (qin[2] * qin[3] + qin[0] * qin[1]);
  374. dcm[6] = 2.0f * (qin[1] * qin[3] + qin[0] * qin[2]);
  375. dcm[7] = 2.0f * (qin[2] * qin[3] - qin[0] * qin[1]);
  376. dcm[8] = qin[0] * qin[0] - qin[1] * qin[1] - qin[2] * qin[2] + qin[3] * qin[3];
  377. }
  378. void multiply3x3T(float *a, float *b, float* dst)
  379. {
  380. dst[0] = a[0] * b[0] + a[1] * b[1] + a[2] * b[2];
  381. dst[1] = a[0] * b[3] + a[1] * b[4] + a[2] * b[5];
  382. dst[2] = a[0] * b[6] + a[1] * b[7] + a[2] * b[8];
  383. dst[3] = a[3] * b[0] + a[4] * b[1] + a[5] * b[2];
  384. dst[4] = a[3] * b[3] + a[4] * b[4] + a[5] * b[5];
  385. dst[5] = a[3] * b[6] + a[4] * b[7] + a[5] * b[8];
  386. dst[6] = a[6] * b[0] + a[7] * b[1] + a[8] * b[2];
  387. dst[7] = a[6] * b[3] + a[7] * b[4] + a[8] * b[5];
  388. dst[8] = a[6] * b[6] + a[7] * b[7] + a[8] * b[8];
  389. }
  390. void deltaAttMatrix(float C_prev[9], float C_now[9], float deltaC[9])
  391. {
  392. //detaC = C_prev'* C;
  393. deltaC[0] = C_now[0] * C_prev[0] + C_now[3] * C_prev[3] + C_now[6] * C_prev[6];
  394. deltaC[1] = C_now[1] * C_prev[0] + C_now[4] * C_prev[3] + C_now[7] * C_prev[6];
  395. deltaC[2] = C_now[2] * C_prev[0] + C_now[5] * C_prev[3] + C_now[8] * C_prev[6];
  396. deltaC[3] = C_now[0] * C_prev[1] + C_now[3] * C_prev[4] + C_now[6] * C_prev[7];
  397. deltaC[4] = C_now[1] * C_prev[1] + C_now[4] * C_prev[4] + C_now[7] * C_prev[7];
  398. deltaC[5] = C_now[2] * C_prev[1] + C_now[5] * C_prev[4] + C_now[8] * C_prev[7];
  399. deltaC[6] = C_now[0] * C_prev[2] + C_now[3] * C_prev[5] + C_now[6] * C_prev[8];
  400. deltaC[7] = C_now[1] * C_prev[2] + C_now[4] * C_prev[5] + C_now[7] * C_prev[8];
  401. deltaC[8] = C_now[2] * C_prev[2] + C_now[5] * C_prev[5] + C_now[8] * C_prev[8];
  402. }
  403. void normVector(float a[3])
  404. {
  405. float norm = 1.0f/sqrt(a[0] * a[0] + a[1] * a[1] + a[2] * a[2]);
  406. a[0] *= norm;
  407. a[1] *= norm;
  408. a[2] *= norm;
  409. }
  410. void resetUKF(float *UKF_Q, float UKF_P[4][4], float *mag_prev, float *mag, float *UKF_C, float *C)
  411. {
  412. memset(UKF_Q, 0, 4 * sizeof(float));
  413. UKF_Q[0] = 1.0f;
  414. memcpy(mag_prev, mag, 3 * sizeof(float));
  415. memcpy(UKF_C, C, 9 * sizeof(float));
  416. for (int i = 0; i < 4; i++)
  417. for (int j = 0; j < 4; j++)
  418. {
  419. UKF_P[i][j] = 0.0f;
  420. }
  421. for (int i = 0; i < 4; i++)
  422. {
  423. UKF_P[i][i] = 0.0000001f;
  424. }
  425. }
  426. //利用陀螺仪的双极端盘判断是否在稳定的范围
  427. int isStandCon(float gyr_extreme[6])
  428. {
  429. DEBUG_LOG(" left_sh , gyr_extreme[1] - gyr_extreme[0] = %d\n",(int)((gyr_extreme[1] - gyr_extreme[0])*1000.f));
  430. DEBUG_LOG(" left_sh , gyr_extreme[1] - gyr_extreme[0] = %d\n",(int)((gyr_extreme[3] - gyr_extreme[2])*1000.f));
  431. DEBUG_LOG(" left_sh , gyr_extreme[1] - gyr_extreme[0] = %d\n",(int)((gyr_extreme[5] - gyr_extreme[4])*1000.f));
  432. if(gyr_extreme[1] - gyr_extreme[0] < 0.02f && gyr_extreme[3] - gyr_extreme[2] < 0.02f && gyr_extreme[5] - gyr_extreme[4] < 0.02f)
  433. {
  434. return 1;
  435. }
  436. return 0;
  437. }
  438. void estimate_gyr_bias(float *gyr)
  439. {
  440. if (num_peak == 0)
  441. {
  442. for (int i = 0; i < 3; i++)
  443. {
  444. gyr_extreme[2 * i] = gyr[i];
  445. gyr_extreme[2 * i + 1] = gyr[i];
  446. }
  447. }
  448. for (int i = 0; i < 3; i++)
  449. {
  450. if (gyr[i] < gyr_extreme[2 * i])
  451. {
  452. gyr_extreme[2 * i] = gyr[i];
  453. }
  454. if (gyr[i] > gyr_extreme[2 * i + 1])
  455. {
  456. gyr_extreme[2 * i + 1] = gyr[i];
  457. }
  458. }
  459. for (int i = 0; i < 3; i++)
  460. {
  461. gyr_mean[i] += gyr[i];
  462. }
  463. num_peak++;
  464. //在线估计陀螺仪的零偏, 6050的零偏偏大
  465. if (num_peak == 1000)
  466. {
  467. if (isStandCon(gyr_extreme))
  468. {
  469. //识别每一次游戏模式下,静止状态的陀螺仪令零偏
  470. for(int i = 0; i < 3; i++)
  471. {
  472. //gyrBias[i] = gyr_mean[i] * 0.0033f;
  473. gyrBias[i] = gyr_mean[i] * 0.001f;
  474. }
  475. DEBUG_LOG("gyrBias has cor!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!\n");
  476. }
  477. num_peak = 0;
  478. memset(gyr_mean, 0, 3 * sizeof(float));
  479. }
  480. }
  481. void estimate_gyr_bias_interface(int16_t *gyr, int sample_count)
  482. {
  483. static float gyr_f[3];
  484. for(int i = 0; i < 3; i++)
  485. {
  486. gyr_f[i] = gyr[i] * 0.0010642251f;
  487. }
  488. if(sample_count == 0)
  489. {
  490. num_peak = 0;
  491. }
  492. estimate_gyr_bias(gyr_f);
  493. }
  494. unsigned char footPDR(uint32_t num, float *gyr, float *acc, uint16_t front_press, int16_t zupt, int16_t acc_zero, int32_t* pos_res, int16_t* att)
  495. {
  496. unsigned char movement_e = 0;
  497. dt = (float)(num - last_timestamp) * 0.000001f;
  498. if(num < last_timestamp || dt > 0.006f)
  499. {
  500. //dt =(float)(4294967295 - last_timestamp + num) * 0.000001f;
  501. dt = 0.0024f;
  502. }
  503. last_timestamp = num;
  504. for (int i = 0; i < 3; i++)
  505. {
  506. gyr[i] *= (PI / 180.0f);
  507. acc[i] *= g;
  508. }
  509. //估计零偏
  510. estimate_gyr_bias(gyr);
  511. gyr[0] -= gyrBias[0];
  512. gyr[1] -= gyrBias[1];
  513. gyr[2] -= gyrBias[2];
  514. //下面为惯导解算
  515. if (frame_index == 0)
  516. {
  517. Initialize(gyr, acc);
  518. frame_index = 1;
  519. return movement_e;
  520. }
  521. //惯导解算: 姿态矩阵更新
  522. attitude_matrix_update(C, Temporary_array1, Temporary_array2, gyr, dt);
  523. //惯导解算: 将IMU坐标系的加速度转换到“导航坐标系”下
  524. multiply3x1(C, acc, acc_n);
  525. //惯导解算: 更新IMU速度
  526. vel_n[0] = vel_n[0] + acc_n[0] * dt;
  527. vel_n[1] = vel_n[1] + acc_n[1] * dt;
  528. vel_n[2] = vel_n[2] + (acc_n[2] - g) * dt;
  529. //惯导解算: 更新IMU位置
  530. pos_n[0] = pos_n[0] + vel_n[0] * dt;
  531. pos_n[1] = pos_n[1] + vel_n[1] * dt;
  532. pos_n[2] = pos_n[2] + vel_n[2] * dt;
  533. //ekf步骤: 状态协方差矩阵预测更新
  534. //P = F*P*F' + Q;
  535. State_covariance_matrix_update(P, acc_n, dt);
  536. //zupt
  537. if (zupt == 1 || acc_zero == 1)
  538. {
  539. //ekf步骤: 计算卡尔曼滤波增益
  540. //K = P*H'/(H*P*H' + R);
  541. calKafmanGain9x4(K, P);
  542. //ekf步骤: 观测误差更新
  543. //delta_x = K * [vel_n(:,i);];
  544. float measure[4];
  545. //设置方向误差为0,意味着不要对heading进行修补
  546. memset(measure, 0, 4 *sizeof(float));
  547. measure[1] = vel_n[0];
  548. measure[2] = vel_n[1];
  549. measure[3] = vel_n[2];
  550. calDeltaX9x4(K, measure, delta_x);
  551. //ekf步骤: 状态协方差矩阵观测更新
  552. calStateCov9x4(P, K);
  553. //修正姿态矩阵
  554. Att_matrix_corr(C, C_prev, Temporary_array1, Temporary_array2, delta_x);
  555. //修正位置
  556. //pos_n_corr(pos_n, delta_x);
  557. //修正速度
  558. vel_n_corr(vel_n, delta_x);
  559. // memset(vel_n, 0, 3 * sizeof(float));
  560. //速度设置为0,因为滤波器收敛会导致轨迹有错误的振荡,实测直接设置为0也是可以的
  561. // float sub_vel[3];
  562. //
  563. // if(zupt_count < 10)
  564. // {
  565. // for(int i = 0; i < 3; i++)
  566. // {
  567. // sub_vel[i] = (1.0f - zupt_count*0.1f)* vel_n[i];
  568. //
  569. // vel_n[i] -= sub_vel[i];
  570. // }
  571. // }
  572. memcpy(last_pos_n, pos_n, 3 * sizeof(float));
  573. zupt_count ++;
  574. }
  575. else
  576. {
  577. if(zupt_count > 0)
  578. {
  579. zupt_count--;
  580. }
  581. }
  582. //状态协方差矩阵保持正交性,以防出现退化
  583. State_covariance_matrix_orthogonalization(P);
  584. pos_offset[0] = pos_offset[0] + pos_n[0] - last_pos_n[0];
  585. pos_offset[1] = pos_offset[1] + pos_n[1] - last_pos_n[1];
  586. pos_offset[2] = pos_offset[2] + pos_n[2] - last_pos_n[2];
  587. memcpy(last_pos_n, pos_n, 3 * sizeof(float));
  588. dcm2angleTest(C, att); //航向角,俯仰角, 翻滚角(z y x)
  589. pos_res[0] = (int32_t) (pos_offset[0] * 1000.0f);
  590. pos_res[1] = (int32_t) (pos_offset[1] * 1000.0f);
  591. pos_res[2] = (int32_t) (pos_offset[2] * 1000.0f);
  592. return movement_e;
  593. }