svpwm.c 3.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148
  1. #include "foc/svpwm.h"
  2. #include "math/fast_math.h"
  3. /* 7段式SVPWM
  4. * 返回设置3相PWM的3个CCR寄存器的值
  5. * 这里使用的是stm32的PWM mode1,在向上计数时,一旦TIMx_CNT<TIMx_CCR1时通道1为有效电平,否则为无效电平
  6. * 在向下计数时,一旦TIMx_CNT>TIMx_CCR1时通道1为无效电平(OC1REF=0),否则为有效 电平(OC1REF=1)。
  7. * 整个时间的计算,前面X,Y,Z都是一样的,后面计算ABC三相的pwm CCR寄存器值的时候,需要注意,很多网络包括书本的资料都是用PWM2模式的
  8. 就是高电平的时间 pwm_period - ccr,我们用PWM1模式,所以最后abc的计算稍微有些不一样
  9. */
  10. void svpwm_get_phase_time(alpha_beta_t *alpha_beta, float vbus, u32 PWM_half_period, phase_time_t *phase_out, u8 *sector_out) {
  11. float alpha = alpha_beta->alpha * SQRT3_BY_2;
  12. float beta = alpha_beta->beta * SQRT3_BY_2;
  13. u32 PWM_Period = PWM_half_period * 2;
  14. u8 sector = 0xFF;
  15. u32 tA, tB, tC;
  16. u32 low, midle, high;
  17. float X, Y, Z;
  18. float modu = (float)(PWM_Period) / vbus;
  19. if (beta >= 0.0f) {
  20. if (alpha >= 0.0f) {
  21. //quadrant I
  22. if (ONE_BY_SQRT3 * beta > alpha) {
  23. sector = SECTOR_2;
  24. } else {
  25. sector = SECTOR_1;
  26. }
  27. } else {
  28. //quadrant II
  29. if (-ONE_BY_SQRT3 * beta > alpha) {
  30. sector = SECTOR_3;
  31. } else {
  32. sector = SECTOR_2;
  33. }
  34. }
  35. } else {
  36. if (alpha >= 0.0f) {
  37. //quadrant IV5
  38. if (-ONE_BY_SQRT3 * beta > alpha) {
  39. sector = SECTOR_5;
  40. } else {
  41. sector = SECTOR_6;
  42. }
  43. } else {
  44. //quadrant III
  45. if (ONE_BY_SQRT3 * beta > alpha) {
  46. sector = SECTOR_4;
  47. } else {
  48. sector = SECTOR_5;
  49. }
  50. }
  51. }
  52. X = TWO_BY_SQRT3 * beta * modu;
  53. Y = (alpha + ONE_BY_SQRT3 * beta) * modu;
  54. Z = (-alpha + ONE_BY_SQRT3 * beta) * modu;
  55. switch(sector) {
  56. case SECTOR_1: // 3
  57. { u32 T4 = -Z;
  58. u32 T6 = X;
  59. tC = (PWM_Period - T4 - T6)/4;
  60. tB = tC + T6/2;
  61. tA = tB + T4/2;
  62. low = tA;
  63. midle = tB;
  64. high = tC;
  65. break;
  66. }
  67. case SECTOR_2: // 1
  68. {
  69. u32 T6 = Y;
  70. u32 T2 = Z;
  71. tC = (PWM_Period - T6 - T2)/4;
  72. tA = tC + T6/2;
  73. tB = tA + T2/2;
  74. low = tB;
  75. midle = tA;
  76. high = tC;
  77. break;
  78. }
  79. case SECTOR_3: // 5
  80. {
  81. u32 T2 = X;
  82. u32 T3 = -Y;
  83. tA = (PWM_Period - T2 - T3)/4;
  84. tC = tA + T3/2;
  85. tB = tC + T2/2;
  86. low = tB;
  87. midle = tC;
  88. high = tA;
  89. break;
  90. }
  91. case SECTOR_4: // 4
  92. {
  93. u32 T1 = -X;
  94. u32 T3 = Z;
  95. tA = (PWM_Period - T1 - T3)/4;
  96. tB = tA + T3/2;
  97. tC = tB + T1/2;
  98. low = tC;
  99. midle = tB;
  100. high = tA;
  101. break;
  102. }
  103. case SECTOR_5: // 6
  104. {
  105. u32 T1 = -Y;
  106. u32 T5 = -Z;
  107. tB = (PWM_Period - T1 - T5)/4;
  108. tA = tB + T5/2;
  109. tC = tA + T1/2;
  110. low = tC;
  111. midle = tA;
  112. high = tB;
  113. break;
  114. }
  115. case SECTOR_6: // 2
  116. {
  117. u32 T4 = Y;
  118. u32 T5 = -X;
  119. tB = (PWM_Period - T4 - T5)/4;
  120. tC = tB + T5/2;
  121. tA = tC + T4/2;
  122. low = tA;
  123. midle = tC;
  124. high = tB;
  125. break;
  126. }
  127. default:
  128. break;
  129. }
  130. phase_out->A = tA;
  131. phase_out->B = tB;
  132. phase_out->C = tC;
  133. phase_out->low = low;
  134. phase_out->midle = midle;
  135. phase_out->high = high;
  136. *sector_out = sector;
  137. #if 0
  138. static int tet_p = 0;
  139. if (tet_p++ % 10 == 0) {
  140. printf("$%d %d %d;", tA, tB, tC);
  141. }
  142. #endif
  143. // printf("3sec %d, A:%d, B:%d, C:%d\n", sector, A_duty, B_duty, C_duty);
  144. }