hall.c 9.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361
  1. #include <string.h>
  2. #include "bsp/bsp_driver.h"
  3. #include "os/os_task.h"
  4. #include "libs/utils.h"
  5. #include "libs/logger.h"
  6. #include "math/fast_math.h"
  7. #include "foc/motor/hall.h"
  8. #include "foc/mc_config.h"
  9. #include "app/nv_storage.h"
  10. #include "libs/logger.h"
  11. #define HALL_READ_TIMES 5
  12. #define SMOOTH_COUNT 0
  13. #define HALL_DETECT_OFFSET 0
  14. /*
  15. 1,5,4,6,2,3
  16. 0,1,2,3,4,5
  17. //////
  18. 2,6,4,5,1,3
  19. 0,1,2,3,4,5
  20. ////
  21. 2,3,1,5,4,6
  22. 0,1,2,3,4,5
  23. */
  24. static s8 hall_2_pos[] = {7,2,0,1,4,3,5,7};
  25. static hall_t g_hall;
  26. #define us_2_s(tick) ((float)tick / 1000000.0f) //s32q14
  27. #define HALL_MAX_TIME 1000000UL
  28. static u32 g_delta_cnt = 0;
  29. static u32 g_trns_cnt = 0;
  30. static u32 g_min_delta;
  31. #define COUNT_2_US(c) (c/(SYSTEM_CLOCK/1000000))
  32. #if HALL_DETECT_OFFSET > 0
  33. static float hall_off[6];
  34. static u32 hall_off_cnt[6];
  35. static void hall_offset_dec_init(void) {
  36. for (int i = 0; i < 6; i++) {
  37. hall_off[i] = 0;
  38. hall_off_cnt[i] = 0;
  39. }
  40. }
  41. float mc_get_mot_angle(void);
  42. static __INLINE void hall_offset_update(void) {
  43. int pos_int = (int)g_hall.low_res_pos;
  44. float hall_pos = g_hall.low_res_pos * PHASE_60_DEGREE;
  45. float delta_pos = hall_pos - (mc_get_mot_angle() + 90.0f);
  46. norm_angle_deg(delta_pos);
  47. hall_off[pos_int] = delta_pos;
  48. hall_off_cnt[pos_int] += 1;
  49. }
  50. static void hall_offset_log(void) {
  51. if (hall_off_cnt[0] < 20) {
  52. return;
  53. }
  54. s16 value[6];
  55. u32 mask = cpu_enter_critical();
  56. for (int i = 0; i < 6; i++) {
  57. value[i] = (s16)(hall_off[i]/(float)hall_off_cnt[i]);
  58. hall_off_cnt[i] = 0;
  59. }
  60. cpu_exit_critical(mask);
  61. sys_debug("off:%d,%d,%d,%d,%d,%d\n", value[0], value[1], value[2], value[3], value[4], value[5]);
  62. }
  63. #else
  64. static void hall_offset_dec_init(void) {
  65. }
  66. static __INLINE void hall_offset_update(void) {
  67. }
  68. static void hall_offset_log(void) {
  69. }
  70. #endif
  71. static __INLINE u32 hall_delta_us(u32 count) {
  72. u32 now = task_ticks_abs();
  73. u32 delta = now - count;
  74. if (now < count) { //wrap
  75. delta = 0xFFFFFFFF - count + now + 1;
  76. }
  77. return COUNT_2_US(delta);
  78. }
  79. static u8 __INLINE hall_read_state(void) {
  80. u8 hall_a = 0, hall_b = 0, hall_c = 0;
  81. for (int i = 0; i < HALL_READ_TIMES; i++) {
  82. hall_a += gpio_hall_a_value();
  83. hall_b += gpio_hall_b_value();
  84. hall_c += gpio_hall_c_value();
  85. }
  86. u8 state = 0;
  87. if (hall_a > (HALL_READ_TIMES/2 + 1)) {
  88. state = 1;
  89. }
  90. if (hall_b > (HALL_READ_TIMES/2 + 1)) {
  91. state = state | (1<<1);
  92. }
  93. if (hall_c > (HALL_READ_TIMES/2 + 1)) {
  94. state = state | (1 << 2);
  95. }
  96. return state;
  97. }
  98. static void hall_init_low_pos(void) {
  99. u8 state = hall_read_state();
  100. s16 pos = hall_2_pos[state];
  101. if (pos == 7) {
  102. g_hall.sig_errors ++;
  103. return;
  104. }
  105. g_hall.state = state;
  106. if (g_hall.dir == POSITIVE) {
  107. g_hall.low_res_pos = pos + 0.5f;
  108. }else {
  109. g_hall.low_res_pos = pos - 0.5f;
  110. }
  111. }
  112. static void __INLINE hall_put_sample(u32 ticks) {
  113. hsample_t *s = &g_hall.samples;
  114. g_hall.last_delta_ticks = ticks;
  115. s->ticks_sum -= s->ticks[s->index];
  116. s->ticks[s->index] = ticks;
  117. s->ticks_sum += s->ticks[s->index];
  118. s->index += 1;
  119. if (s->index >= SAMPLE_MAX_COUNT) {
  120. s->index = 0;
  121. }
  122. if (s->filled < SAMPLE_MAX_COUNT) {
  123. s->filled++;
  124. }
  125. }
  126. static float __INLINE hall_elec_angle_vel(void){
  127. hsample_t *s = &g_hall.samples;
  128. if (s->filled < SAMPLE_MAX_COUNT) {
  129. return (PHASE_60_DEGREE) / us_2_s(g_hall.last_delta_ticks);
  130. }
  131. if (s->ticks_sum == 0) {
  132. return 0.0f;
  133. }
  134. return (PHASE_60_DEGREE * SAMPLE_MAX_COUNT) / us_2_s(s->ticks_sum);
  135. }
  136. void hall_debug_log(void) {
  137. sys_debug("angle dir %d, stat %d, lowres %f, err %d,%d\n", g_hall.dir, g_hall.state, g_hall.low_res_pos, g_hall.sig_errors, g_hall.noise_errors);
  138. sys_debug("D: %d,%d,%d\n", g_delta_cnt, g_trns_cnt, g_min_delta);
  139. sys_debug("RPM: %f\n", hall_get_velocity());
  140. hall_offset_log();
  141. }
  142. void hall_init(void) {
  143. g_hall.phase_offset = mc_conf()->m.encoder_offset;
  144. g_hall.mot_poles = mc_conf()->m.poles;
  145. g_hall.b_trns_det = false;
  146. g_hall.angle_smooth_cnt = SMOOTH_COUNT + 1;
  147. g_hall.angle_smooth_step = 0;
  148. g_hall.samples.ticks_sum = 0;
  149. g_hall.position = 0;
  150. g_hall.samples.index = 0;
  151. g_hall.samples.filled = 0;
  152. g_hall.elec_angle_vel = 0;
  153. g_hall.edge_ticks = 0;
  154. g_hall.dir_set = g_hall.prev_dir = g_hall.dir = POSITIVE;
  155. g_min_delta = 1000000 * 100;
  156. for (int i = 0; i < SAMPLE_MAX_COUNT; i++) {
  157. g_hall.samples.ticks[i] = HALL_MAX_TIME;
  158. }
  159. g_hall.samples.ticks_sum = HALL_MAX_TIME * SAMPLE_MAX_COUNT;
  160. if (!g_hall.inited) {
  161. g_hall.inited = true;
  162. #ifdef HALL_TIMER
  163. hall_tmr_init();
  164. #else
  165. gpio_hall_init();
  166. #endif
  167. }
  168. hall_offset_dec_init();
  169. hall_init_low_pos();
  170. }
  171. void hall_set_direction(s8 dir) {
  172. if (dir == g_hall.dir_set) {
  173. return;
  174. }
  175. g_hall.dir_set = g_hall.dir = g_hall.prev_dir = dir;
  176. hall_init_low_pos();
  177. }
  178. #if SMOOTH_COUNT > 0
  179. static float get_angle_diff(float a1, float a2) {
  180. float diff = a1 - a2;
  181. float abs_diff = ABS(diff);
  182. if (abs_diff >= PHASE_180_DEGREE) {
  183. return (PHASE_360_DEGREE - abs_diff);
  184. }else {
  185. return diff;
  186. }
  187. }
  188. #endif
  189. static __INLINE bool hall_update_low_pos(void) {
  190. u8 state = hall_read_state();
  191. s16 pos = hall_2_pos[state];
  192. if (pos == 7) {
  193. g_hall.sig_errors ++;
  194. return false;
  195. }
  196. s16 pos_prev = hall_2_pos[g_hall.state];
  197. s16 delta_pos = pos - pos_prev;
  198. if (delta_pos != 0) {
  199. s8 prev_dir = g_hall.dir;
  200. if (delta_pos == 1 || delta_pos == -5) {
  201. g_hall.dir = POSITIVE;
  202. g_hall.prev_dir = prev_dir;
  203. }else if (delta_pos == -1 || delta_pos == 5){
  204. g_hall.dir = NEGATIVE;
  205. g_hall.prev_dir = prev_dir;
  206. }else {
  207. if (g_hall.samples.filled > 0) {
  208. g_hall.sig_errors ++;
  209. return false;
  210. }
  211. }
  212. g_hall.edge_ticks = task_ticks_abs();
  213. }else {
  214. g_hall.sig_errors ++;
  215. return false;
  216. }
  217. g_hall.state = state;
  218. g_hall.low_res_pos = pos;
  219. return true;
  220. }
  221. hall_t *hall_get(void) {
  222. return &g_hall;
  223. }
  224. float hall_get_elec_angle(void) {
  225. float phase_offset = g_hall.phase_offset;
  226. if (g_hall.dir == NEGATIVE) {
  227. phase_offset = PHASE_60_DEGREE + phase_offset;
  228. }
  229. float angle = g_hall.elec_angle + phase_offset;
  230. norm_angle_deg(angle);
  231. return angle;
  232. }
  233. float hall_update_elec_angle(void) {
  234. float delta_ticks = (float)hall_delta_us(g_hall.edge_ticks);//上次hall变换到目前的时间
  235. float low_res = g_hall.low_res_pos;
  236. float delta_pos = g_hall.elec_angle_vel / PHASE_60_DEGREE * us_2_s(delta_ticks) * g_hall.dir;//上次hall变换到目前走过的角度(对60度的比值,小于1),通过速度插值
  237. if (delta_pos > 1.0f) {
  238. delta_pos = 1.0f;
  239. }else if (delta_pos < -1.0f) {
  240. delta_pos = -1.0f;
  241. }
  242. float high_res_pos = delta_pos + low_res;
  243. float elec_angle = high_res_pos * PHASE_60_DEGREE;
  244. float elec_smooth_angle;
  245. #if SMOOTH_COUNT>0
  246. float delta_angle = delta_pos * PHASE_60_DEGREE;
  247. if (g_hall.angle_smooth_cnt < (SMOOTH_COUNT + 1)) {
  248. elec_smooth_angle = g_hall.elec_angle_edge + g_hall.angle_smooth_step * g_hall.angle_smooth_cnt + delta_angle;
  249. g_hall.angle_smooth_cnt++;
  250. if (g_hall.angle_smooth_step >= 0) {
  251. elec_smooth_angle = min(elec_smooth_angle, elec_angle);
  252. }else {
  253. elec_smooth_angle = MAX(elec_smooth_angle, elec_angle);
  254. }
  255. }else {
  256. elec_smooth_angle = elec_angle;
  257. }
  258. #else
  259. elec_smooth_angle = elec_angle;
  260. #endif
  261. norm_angle_deg(elec_smooth_angle);
  262. g_hall.elec_angle = elec_smooth_angle;
  263. g_hall.position += g_hall.elec_angle_vel * FOC_CTRL_US / g_hall.mot_poles;
  264. if ((g_hall.elec_angle_vel > 0.000001f) && (delta_ticks >= HALL_MAX_TIME)) {
  265. g_hall.elec_angle_vel = 0;
  266. g_hall.samples.filled = 0;
  267. g_hall.samples.index = 0;
  268. g_hall.velocity_filted = 0;
  269. g_hall.dir = g_hall.prev_dir = g_hall.dir_set;
  270. hall_init_low_pos();
  271. }
  272. return hall_get_elec_angle();
  273. }
  274. float hall_get_vel_counts(void) {
  275. return g_hall.elec_angle_vel/PHASE_60_DEGREE * g_hall.dir;
  276. }
  277. float hall_get_velocity(void) {
  278. return g_hall.velocity_filted;
  279. }
  280. float hall_get_position(void) {
  281. return g_hall.position;
  282. }
  283. static __INLINE void hall_calc_mot_velocity(u32 delta_cnt) {
  284. if (g_hall.samples.filled == 0) {
  285. hall_put_sample(HALL_MAX_TIME/10);
  286. return;
  287. }
  288. if (delta_cnt < g_min_delta) {
  289. g_min_delta = delta_cnt;
  290. }
  291. hall_put_sample(delta_cnt);
  292. g_hall.elec_angle_vel = hall_elec_angle_vel();
  293. float velocity_raw = g_hall.elec_angle_vel/PHASE_360_DEGREE/g_hall.mot_poles * 60.0f * g_hall.dir;
  294. LowPass_Filter(g_hall.velocity_filted, velocity_raw, 0.5F);
  295. }
  296. float hall_offset_detect(float *off) {
  297. return 0.0f;
  298. }
  299. void HALL_IRQHandler(void) {
  300. g_delta_cnt++;
  301. u32 mask = cpu_enter_critical();
  302. u32 delta_cnt = hall_delta_us(g_hall.edge_ticks);
  303. if (delta_cnt < 200) { //1200rpm, 30 poles
  304. g_hall.noise_errors++;
  305. goto hall_end;
  306. }
  307. if (!hall_update_low_pos()) {
  308. goto hall_end;
  309. }
  310. hall_offset_update();
  311. g_hall.elec_angle_edge = g_hall.elec_angle;
  312. #if SMOOTH_COUNT>0
  313. g_hall.delta_angle_edge = get_angle_diff(g_hall.low_res_pos * PHASE_60_DEGREE, g_hall.elec_angle_edge);
  314. if (ABS(g_hall.delta_angle_edge) >= 2.0f) {
  315. g_hall.angle_smooth_step = g_hall.delta_angle_edge/SMOOTH_COUNT;
  316. g_hall.angle_smooth_cnt = 1;
  317. }else {
  318. g_hall.angle_smooth_step = 0;
  319. g_hall.angle_smooth_cnt = SMOOTH_COUNT + 1;
  320. }
  321. #endif
  322. hall_calc_mot_velocity(delta_cnt);
  323. hall_end:
  324. cpu_exit_critical(mask);
  325. return;
  326. }