footPDR.c 23 KB

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