dspb16.h 17 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495
  1. /****************************************************************************
  2. * include/dspb16.h
  3. *
  4. * Licensed to the Apache Software Foundation (ASF) under one or more
  5. * contributor license agreements. See the NOTICE file distributed with
  6. * this work for additional information regarding copyright ownership. The
  7. * ASF licenses this file to you under the Apache License, Version 2.0 (the
  8. * "License"); you may not use this file except in compliance with the
  9. * License. You may obtain a copy of the License at
  10. *
  11. * http://www.apache.org/licenses/LICENSE-2.0
  12. *
  13. * Unless required by applicable law or agreed to in writing, software
  14. * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
  15. * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
  16. * License for the specific language governing permissions and limitations
  17. * under the License.
  18. *
  19. ****************************************************************************/
  20. #ifndef __INCLUDE_DSPB16_H
  21. #define __INCLUDE_DSPB16_H
  22. /****************************************************************************
  23. * Included Files
  24. ****************************************************************************/
  25. #include <nuttx/compiler.h>
  26. #include <stddef.h>
  27. #include <stdint.h>
  28. #include <string.h>
  29. #include <stdbool.h>
  30. #include <fixedmath.h>
  31. #include <assert.h>
  32. /****************************************************************************
  33. * Pre-processor Definitions
  34. ****************************************************************************/
  35. /* Disable DEBUGASSERT macro if LIBDSP debug is not enabled */
  36. #ifdef CONFIG_LIBDSP_DEBUG
  37. # ifndef CONFIG_DEBUG_ASSERTIONS
  38. # warning "Need CONFIG_DEBUG_ASSERTIONS to work properly"
  39. # endif
  40. # define LIBDSP_DEBUGASSERT(x) DEBUGASSERT(x)
  41. #else
  42. # undef LIBDSP_DEBUGASSERT
  43. # define LIBDSP_DEBUGASSERT(x)
  44. #endif
  45. #ifndef CONFIG_LIBDSP_PRECISION
  46. # define CONFIG_LIBDSP_PRECISION 0
  47. #endif
  48. /* Phase rotation direction */
  49. #define DIR_NONE_B16 ftob16(0.0f)
  50. #define DIR_CW_B16 ftob16(1.0f)
  51. #define DIR_CCW_B16 ftob16(-1.0f)
  52. /* Some math constants ******************************************************/
  53. #define SQRT3_BY_TWO_B16 ftob16(0.866025f)
  54. #define SQRT3_BY_THREE_B16 ftob16(0.57735f)
  55. #define ONE_BY_SQRT3_B16 ftob16(0.57735f)
  56. #define TWO_BY_SQRT3_B16 ftob16(1.15470f)
  57. /* Some lib constants *******************************************************/
  58. /* Motor electrical angle is in range 0.0 to 2*PI */
  59. #define MOTOR_ANGLE_E_MAX_B16 (b16TWOPI)
  60. #define MOTOR_ANGLE_E_MIN_B16 (0)
  61. #define MOTOR_ANGLE_E_RANGE_B16 (MOTOR_ANGLE_E_MAX_B16 - MOTOR_ANGLE_E_MIN_B16)
  62. /* Motor mechanical angle is in range 0.0 to 2*PI */
  63. #define MOTOR_ANGLE_M_MAX_B16 (b16TWOPI)
  64. #define MOTOR_ANGLE_M_MIN_B16 (0)
  65. #define MOTOR_ANGLE_M_RANGE_B16 (MOTOR_ANGLE_M_MAX_B16 - MOTOR_ANGLE_M_MIN_B16)
  66. /* Some useful macros *******************************************************/
  67. /****************************************************************************
  68. * Name: LP_FILTER_B16
  69. *
  70. * Description:
  71. * Simple single-pole digital low pass filter:
  72. * Y(n) = (1-beta)*Y(n-1) + beta*X(n) = (beta * (Y(n-1) - X(n)))
  73. *
  74. * filter - (0.0 - 1.0) where 1.0 gives unfiltered values
  75. * filter = T * (2*PI) * f_c
  76. *
  77. * phase shift = -arctan(f_in/f_c)
  78. *
  79. * T - period at which the digital filter is being calculated
  80. * f_in - input frequency of the filter
  81. * f_c - cutoff frequency of the filter
  82. *
  83. * REFERENCE: https://www.embeddedrelated.com/showarticle/779.php
  84. *
  85. ****************************************************************************/
  86. #define LP_FILTER_B16(val, sample, filter) val -= (b16mulb16(filter, (val - sample)))
  87. /****************************************************************************
  88. * Name: SVM3_BASE_VOLTAGE_GET_B16
  89. *
  90. * Description:
  91. * Get maximum voltage for SVM3 without overmodulation
  92. *
  93. * Notes:
  94. * max possible phase voltage for 3-phase power inverter:
  95. * Vd = (2/3)*Vdc
  96. * max phase reference voltage according to SVM modulation diagram:
  97. * Vrefmax = Vd * cos(30*) = SQRT3_BY_2 * Vd
  98. * which give us:
  99. * Vrefmax = SQRT3_BY_3 * Vdc
  100. *
  101. * Vdc - bus voltage
  102. *
  103. ****************************************************************************/
  104. #define SVM3_BASE_VOLTAGE_GET_B16(vbus) (b16mulb16(vbus, SQRT3_BY_THREE_B16))
  105. /****************************************************************************
  106. * Public Types
  107. ****************************************************************************/
  108. /* This structure represents phase angle.
  109. * Besides angle value it also stores sine and cosine values for given angle.
  110. */
  111. struct phase_angle_b16_s
  112. {
  113. b16_t angle; /* Phase angle in radians <0, 2PI> */
  114. b16_t sin; /* Phase angle sine */
  115. b16_t cos; /* Phase angle cosine */
  116. };
  117. typedef struct phase_angle_b16_s phase_angle_b16_t;
  118. /* This structure stores motor angles and corresponding sin and cos values
  119. *
  120. * th_el = th_m * pole_pairs
  121. * th_m = th_el/pole_pairs
  122. *
  123. * where:
  124. * th_el - motor electrical angle
  125. * th_m - motor mechanical angle
  126. * pole_pairs - motor pole pairs
  127. *
  128. * NOTE: pole_pairs = poles_total/2
  129. */
  130. struct motor_angle_b16_s
  131. {
  132. phase_angle_b16_t angle_el; /* Electrical angle */
  133. b16_t anglem; /* Mechanical angle in radians <0, 2PI> */
  134. b16_t one_by_p; /* Aux variable */
  135. uint8_t p; /* Number of the motor pole pairs */
  136. int8_t i; /* Pole counter */
  137. };
  138. /* Float number saturaton */
  139. struct float_sat_b16_s
  140. {
  141. b16_t min; /* Lower limit */
  142. b16_t max; /* Upper limit */
  143. };
  144. typedef struct float_sat_b16_s float_sat_b16_t;
  145. /* PI/PID controller state structure */
  146. struct pid_controller_b16_s
  147. {
  148. bool aw_en; /* Integral part decay if saturated */
  149. bool ireset_en; /* Intergral part reset if saturated */
  150. bool pisat_en; /* PI saturation enabled */
  151. bool pidsat_en; /* PID saturation enabled */
  152. bool _res; /* Reserved */
  153. b16_t out; /* Controller output */
  154. float_sat_b16_t sat; /* Output saturation */
  155. b16_t err; /* Current error value */
  156. b16_t err_prev; /* Previous error value */
  157. b16_t KP; /* Proportional coefficient */
  158. b16_t KI; /* Integral coefficient */
  159. b16_t KD; /* Derivative coefficient */
  160. b16_t part[3]; /* 0 - proporitonal part
  161. * 1 - integral part
  162. * 2 - derivative part
  163. */
  164. b16_t KC; /* Integral anti-windup decay coefficient */
  165. b16_t aw; /* Integral anti-windup decay part */
  166. };
  167. typedef struct pid_controller_b16_s pid_controller_b16_t;
  168. /* This structure represents the ABC frame (3 phase vector) */
  169. struct abc_frame_b16_s
  170. {
  171. b16_t a; /* A component */
  172. b16_t b; /* B component */
  173. b16_t c; /* C component */
  174. };
  175. typedef struct abc_frame_b16_s abc_frame_b16_t;
  176. /* This structure represents the alpha-beta frame (2 phase vector) */
  177. struct ab_frame_b16_s
  178. {
  179. b16_t a; /* Alpha component */
  180. b16_t b; /* Beta component */
  181. };
  182. typedef struct ab_frame_b16_s ab_frame_b16_t;
  183. /* This structure represent the direct-quadrature frame */
  184. struct dq_frame_b16_s
  185. {
  186. b16_t d; /* Driect component */
  187. b16_t q; /* Quadrature component */
  188. };
  189. typedef struct dq_frame_b16_s dq_frame_b16_t;
  190. /* Space Vector Modulation data for 3-phase system */
  191. struct svm3_state_b16_s
  192. {
  193. uint8_t sector; /* Current space vector sector */
  194. b16_t d_u; /* Duty cycle for phase U */
  195. b16_t d_v; /* Duty cycle for phase V */
  196. b16_t d_w; /* Duty cycle for phase W */
  197. };
  198. /* Motor open-loop control data */
  199. struct openloop_data_b16_s
  200. {
  201. b16_t angle; /* Open-loop current angle normalized to <0.0, 2PI> */
  202. b16_t per; /* Open-loop control execution period */
  203. };
  204. /* FOC initialize data */
  205. struct foc_initdata_b16_s
  206. {
  207. b16_t id_kp; /* KP for d current */
  208. b16_t id_ki; /* KI for d current */
  209. b16_t iq_kp; /* KP for q current */
  210. b16_t iq_ki; /* KI for q current */
  211. };
  212. /* Field Oriented Control (FOC) data */
  213. struct foc_data_b16_s
  214. {
  215. abc_frame_b16_t v_abc; /* Voltage in ABC frame */
  216. ab_frame_b16_t v_ab; /* Voltage in alpha-beta frame */
  217. dq_frame_b16_t v_dq; /* Requested voltage in dq frame */
  218. ab_frame_b16_t v_ab_mod; /* Modulation voltage normalized to
  219. * magnitude (0.0, 1.0)
  220. */
  221. abc_frame_b16_t i_abc; /* Current in ABC frame */
  222. ab_frame_b16_t i_ab; /* Current in alpha-beta frame */
  223. dq_frame_b16_t i_dq; /* Current in dq frame */
  224. dq_frame_b16_t i_dq_err; /* DQ current error */
  225. dq_frame_b16_t i_dq_ref; /* Requested current for the FOC
  226. * current controller
  227. */
  228. pid_controller_b16_t id_pid; /* Current d-axis component PI controller */
  229. pid_controller_b16_t iq_pid; /* Current q-axis component PI controller */
  230. b16_t vdq_mag_max; /* Maximum dq voltage magnitude */
  231. b16_t vab_mod_scale; /* Voltage alpha-beta modulation scale */
  232. phase_angle_b16_t angle; /* Phase angle */
  233. };
  234. /* Motor physical parameters.
  235. * This data structure was designed to work with BLDC/PMSM motors,
  236. * but probably can be used to describe different types of motors.
  237. */
  238. struct motor_phy_params_b16_s
  239. {
  240. uint8_t p; /* Number of the motor pole pairs */
  241. b16_t res; /* Phase-to-neutral temperature compensated
  242. * resistance
  243. */
  244. b16_t ind; /* Average phase-to-neutral inductance */
  245. b16_t one_by_ind; /* Inverse phase-to-neutral inductance */
  246. };
  247. /* PMSM motor physcial parameters */
  248. struct pmsm_phy_params_b16_s
  249. {
  250. struct motor_phy_params_b16_s motor; /* Motor common PHY */
  251. b16_t iner; /* Rotor inertia */
  252. b16_t flux_link; /* Flux linkage */
  253. b16_t ind_d; /* d-inductance */
  254. b16_t ind_q; /* q-inductance */
  255. b16_t one_by_iner; /* One by J */
  256. b16_t one_by_indd; /* One by Ld */
  257. b16_t one_by_indq; /* One by Lq */
  258. };
  259. /* PMSM motor model state */
  260. struct pmsm_model_state_b16_s
  261. {
  262. /* Motor model phase current */
  263. abc_frame_b16_t i_abc;
  264. ab_frame_b16_t i_ab;
  265. dq_frame_b16_t i_dq;
  266. /* Motor model phase voltage */
  267. abc_frame_b16_t v_abc;
  268. ab_frame_b16_t v_ab;
  269. dq_frame_b16_t v_dq;
  270. /* Motor model angle */
  271. struct motor_angle_b16_s angle;
  272. /* Angular speed */
  273. b16_t omega_e;
  274. b16_t omega_m;
  275. };
  276. /* PMSM motor model external conditions */
  277. struct pmsm_model_ext_b16_s
  278. {
  279. b16_t load; /* Motor model load torque */
  280. };
  281. /* PMSM motor model */
  282. struct pmsm_model_b16_s
  283. {
  284. struct pmsm_phy_params_b16_s phy; /* Motor model physical parameters */
  285. struct pmsm_model_state_b16_s state; /* Motor model state */
  286. struct pmsm_model_ext_b16_s ext; /* Motor model external conditions */
  287. b16_t per; /* Control period */
  288. b16_t id_int; /* Id integral part */
  289. b16_t iq_int; /* Iq integral part */
  290. };
  291. /****************************************************************************
  292. * Public Functions Prototypes
  293. ****************************************************************************/
  294. #undef EXTERN
  295. #if defined(__cplusplus)
  296. #define EXTERN extern "C"
  297. extern "C"
  298. {
  299. #else
  300. #define EXTERN extern
  301. #endif
  302. /* Math functions */
  303. b16_t fast_sin_b16(b16_t angle);
  304. b16_t fast_sin2_b16(b16_t angle);
  305. b16_t fast_cos_b16(b16_t angle);
  306. b16_t fast_cos2_b16(b16_t angle);
  307. b16_t fast_atan2_b16(b16_t y, b16_t x);
  308. void f_saturate_b16(FAR b16_t *val, b16_t min, b16_t max);
  309. b16_t vector2d_mag_b16(b16_t x, b16_t y);
  310. void vector2d_saturate_b16(FAR b16_t *x, FAR b16_t *y, b16_t max);
  311. void dq_saturate_b16(FAR dq_frame_b16_t *dq, b16_t max);
  312. b16_t dq_mag_b16(FAR dq_frame_b16_t *dq);
  313. /* PID controller functions */
  314. void pid_controller_init_b16(FAR pid_controller_b16_t *pid,
  315. b16_t KP, b16_t KI, b16_t KD);
  316. void pi_controller_init_b16(FAR pid_controller_b16_t *pid,
  317. b16_t KP, b16_t KI);
  318. void pid_saturation_set_b16(FAR pid_controller_b16_t *pid, b16_t min,
  319. b16_t max);
  320. void pi_saturation_set_b16(FAR pid_controller_b16_t *pid, b16_t min,
  321. b16_t max);
  322. void pid_integral_reset_b16(FAR pid_controller_b16_t *pid);
  323. void pi_integral_reset_b16(FAR pid_controller_b16_t *pid);
  324. b16_t pi_controller_b16(FAR pid_controller_b16_t *pid, b16_t err);
  325. b16_t pid_controller_b16(FAR pid_controller_b16_t *pid, b16_t err);
  326. void pi_antiwindup_enable_b16(FAR pid_controller_b16_t *pid, b16_t KC,
  327. bool enable);
  328. void pi_ireset_enable_b16(FAR pid_controller_b16_t *pid, bool enable);
  329. /* Transformation functions */
  330. void clarke_transform_b16(FAR abc_frame_b16_t *abc, FAR ab_frame_b16_t *ab);
  331. void inv_clarke_transform_b16(FAR ab_frame_b16_t *ab,
  332. FAR abc_frame_b16_t *abc);
  333. void park_transform_b16(FAR phase_angle_b16_t *angle, FAR ab_frame_b16_t *ab,
  334. FAR dq_frame_b16_t *dq);
  335. void inv_park_transform_b16(FAR phase_angle_b16_t *angle,
  336. FAR dq_frame_b16_t *dq, FAR ab_frame_b16_t *ab);
  337. /* Phase angle related functions */
  338. void angle_norm_b16(FAR b16_t *angle, b16_t per, b16_t bottom, b16_t top);
  339. void angle_norm_2pi_b16(FAR b16_t *angle, b16_t bottom, b16_t top);
  340. void phase_angle_update_b16(FAR struct phase_angle_b16_s *angle, b16_t val);
  341. /* 3-phase system space vector modulation */
  342. void svm3_init_b16(FAR struct svm3_state_b16_s *s);
  343. void svm3_b16(FAR struct svm3_state_b16_s *s, FAR ab_frame_b16_t *ab);
  344. void svm3_current_correct_b16(FAR struct svm3_state_b16_s *s,
  345. b16_t *c0, b16_t *c1, b16_t *c2);
  346. /* Field Oriented Control */
  347. void foc_init_b16(FAR struct foc_data_b16_s *foc,
  348. FAR struct foc_initdata_b16_s *init);
  349. void foc_vbase_update_b16(FAR struct foc_data_b16_s *foc, b16_t vbase);
  350. void foc_angle_update_b16(FAR struct foc_data_b16_s *foc,
  351. FAR phase_angle_b16_t *angle);
  352. void foc_iabc_update_b16(FAR struct foc_data_b16_s *foc,
  353. FAR abc_frame_b16_t *i_abc);
  354. void foc_voltage_control_b16(FAR struct foc_data_b16_s *foc,
  355. FAR dq_frame_b16_t *vdq_ref);
  356. void foc_current_control_b16(FAR struct foc_data_b16_s *foc,
  357. FAR dq_frame_b16_t *idq_ref,
  358. FAR dq_frame_b16_t *vdq_comp,
  359. FAR dq_frame_b16_t *v_dq_ref);
  360. void foc_vabmod_get_b16(FAR struct foc_data_b16_s *foc,
  361. FAR ab_frame_b16_t *v_ab_mod);
  362. void foc_vdq_mag_max_get_b16(FAR struct foc_data_b16_s *foc, FAR b16_t *max);
  363. /* Motor openloop control */
  364. void motor_openloop_init_b16(FAR struct openloop_data_b16_s *op, b16_t per);
  365. void motor_openloop_b16(FAR struct openloop_data_b16_s *op, b16_t speed,
  366. b16_t dir);
  367. b16_t motor_openloop_angle_get_b16(FAR struct openloop_data_b16_s *op);
  368. /* Motor angle */
  369. void motor_angle_init_b16(FAR struct motor_angle_b16_s *angle, uint8_t p);
  370. void motor_angle_e_update_b16(FAR struct motor_angle_b16_s *angle,
  371. b16_t angle_new, b16_t dir);
  372. void motor_angle_m_update_b16(FAR struct motor_angle_b16_s *angle,
  373. b16_t angle_new, b16_t dir);
  374. b16_t motor_angle_m_get_b16(FAR struct motor_angle_b16_s *angle);
  375. b16_t motor_angle_e_get_b16(FAR struct motor_angle_b16_s *angle);
  376. /* Motor physical parameters */
  377. void motor_phy_params_init_b16(FAR struct motor_phy_params_b16_s *phy,
  378. uint8_t poles, b16_t res, b16_t ind);
  379. /* PMSM physical parameters functions */
  380. void pmsm_phy_params_init_b16(FAR struct pmsm_phy_params_b16_s *phy,
  381. uint8_t poles, b16_t res, b16_t ind,
  382. b16_t iner, b16_t flux,
  383. b16_t ind_d, b16_t ind_q);
  384. /* PMSM motor model */
  385. int pmsm_model_initialize_b16(FAR struct pmsm_model_b16_s *model,
  386. FAR struct pmsm_phy_params_b16_s *phy,
  387. b16_t per);
  388. int pmsm_model_elec_b16(FAR struct pmsm_model_b16_s *model,
  389. FAR ab_frame_b16_t *vab);
  390. int pmsm_model_mech_b16(FAR struct pmsm_model_b16_s *model, b16_t load);
  391. #undef EXTERN
  392. #if defined(__cplusplus)
  393. }
  394. #endif
  395. #endif /* __INCLUDE_DSPB16_H */