footPDR.c 20 KB

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