dcmotor.h 9.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257
  1. /*********************************************************************
  2. *
  3. * DC motor library for Fraise pic18f device
  4. *
  5. *
  6. *********************************************************************
  7. * Author Date Comment
  8. *~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
  9. * Antoine Rousseau 2014 Original.
  10. ********************************************************************/
  11. /*
  12. # This program is free software; you can redistribute it and/or
  13. # modify it under the terms of the GNU General Public License
  14. # as published by the Free Software Foundation; either version 2
  15. # of the License, or (at your option) any later version.
  16. #
  17. # This program is distributed in the hope that it will be useful,
  18. # but WITHOUT ANY WARRANTY; without even the implied warranty of
  19. # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  20. # GNU General Public License for more details.
  21. # You should have received a copy of the GNU General Public License
  22. # along with this program; if not, write to the Free Software
  23. # Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
  24. # MA 02110-1301, USA.
  25. */
  26. #ifndef _DCMOTOR_H_
  27. #define _DCMOTOR_H_
  28. #include <fruit.h>
  29. #include <pid.h>
  30. #include <ramp.h>
  31. typedef union{
  32. unsigned char val;
  33. struct {
  34. unsigned incA:1;
  35. unsigned incB:1;
  36. unsigned lastA:1;
  37. unsigned lastB:1;
  38. };
  39. } t_dcmotorIncr;
  40. typedef struct {
  41. int SpeedConsign;
  42. int PWMConsign;
  43. long int lastIncDeltaT; // interval between incs on last Compute() call
  44. long int lastPosition; // position on last Compute() call
  45. unsigned stalled:1; // the motor doesn't run anymore
  46. } t_dcmotorVars;
  47. typedef struct {
  48. long int lastIncTime; // last inc event time
  49. long int IncDeltaT; // interval between last captured inc and the one captured just before the last reset.
  50. // Must be reset in critical section, when reading Position.
  51. long int Position;
  52. union{
  53. unsigned char flags;
  54. struct {
  55. unsigned homed:1 ; //homing done : end switch has been detected.
  56. unsigned direction:1; // last measured direction ; 0=position_decrease 1=position_increase
  57. unsigned end:1;
  58. };
  59. };
  60. } t_dcmotorVolVars;
  61. typedef struct {
  62. unsigned char Mode ; //0:pwm 1:speed 2:pos 3:pos+speed_regulator
  63. int PosWindow; // tolerated absolute position error
  64. int PwmMin; // minimum absolute pwm value
  65. unsigned char StallTime; // if position has not changed during this period, the motor is considered stopped. unit = 1/8 s.
  66. unsigned char PosErrorGain; // position error multiplier before PosPID
  67. union{
  68. unsigned char flags;
  69. struct {
  70. unsigned reversed:1; // 1 if positive speed decreases measured position
  71. unsigned onlyPositive:1; // motor position is not allowed to be negative : when pos==0 only positive speed is allowed.
  72. };
  73. };
  74. } t_dcmotorSetting;
  75. typedef struct {
  76. t_dcmotorSetting Setting;
  77. t_dcmotorIncr Incr;
  78. t_dcmotorVars Vars;
  79. volatile t_dcmotorVolVars VolVars;
  80. t_ramp PosRamp;
  81. t_pid PosPID; //position pid
  82. t_pid SpeedPID; //speed pid
  83. } t_dcmotor ;
  84. extern int dcmotor_v,dcmotor_vabs;
  85. extern t_dcmotorVars dcmotorVars;
  86. extern t_dcmotorVolVars dcmotorVolVars;
  87. // I'm really don't know why compiler complains if I use a 1 arg macro for INIT_PWM_...
  88. #define INIT_PWM_(pwm,unused) do{CCP##pwm##CON = 0b00001100;} while(0) /* single PWM active high*/
  89. #define INIT_PWM(pwm) CALL_FUN2(INIT_PWM_,pwm,0)
  90. #define SET_PWM_(pwm,val) do{ CCP##pwm##CONbits.DC##pwm##B1 = val&2; CCP##pwm##CONbits.DC##pwm##B0 = val&1; CCPR##pwm##L=val>>2; } while(0)
  91. #define SET_PWM(pwm,val) CALL_FUN2(SET_PWM_, pwm, val)
  92. #define DCMOTOR_DECLARE_(motID) t_dcmotor dcmotor##motID
  93. #define DCMOTOR_DECLARE(motID) CALL_FUN(DCMOTOR_DECLARE_,motID)
  94. #define DCMOTOR_CAPTURE_SERVICE_(motID) do{ \
  95. dcmotor##motID.Incr.incA = digitalRead(MOT##motID##_A); \
  96. if(digitalRead(MOT##motID##_END) == MOT##motID##_ENDLEVEL) { \
  97. dcmotor##motID.VolVars.Position = 0; \
  98. dcmotor##motID.VolVars.homed = 1; \
  99. dcmotor##motID.VolVars.end = 1; \
  100. } else dcmotor##motID.VolVars.end = 0; \
  101. if(dcmotor##motID.Incr.incA != dcmotor##motID.Incr.lastA) { \
  102. dcmotor##motID.Incr.lastA = dcmotor##motID.Incr.incA; \
  103. dcmotor##motID.VolVars.IncDeltaT -= dcmotor##motID.VolVars.lastIncTime; \
  104. dcmotor##motID.VolVars.lastIncTime = timeISR(); \
  105. dcmotor##motID.VolVars.IncDeltaT += timeISR(); \
  106. dcmotor##motID.Incr.incB = digitalRead(MOT##motID##_B); \
  107. if(dcmotor##motID.Incr.incA ^ !dcmotor##motID.Incr.incB) { \
  108. dcmotor##motID.VolVars.Position++; \
  109. dcmotor##motID.VolVars.direction = 1; \
  110. } \
  111. else { \
  112. dcmotor##motID.VolVars.Position--; \
  113. dcmotor##motID.VolVars.direction = 0; \
  114. } \
  115. } \
  116. } while(0)
  117. #define DCMOTOR_CAPTURE_SERVICE(motID) CALL_FUN(DCMOTOR_CAPTURE_SERVICE_,motID)
  118. #define DCMOTOR_CAPTURE_SERVICE_SINGLE_(motID) do{ \
  119. dcmotor##motID.Incr.incA = digitalRead(MOT##motID##_A); \
  120. if(digitalRead(MOT##motID##_END) == MOT##motID##_ENDLEVEL) { \
  121. dcmotor##motID.VolVars.Position = 0; \
  122. dcmotor##motID.VolVars.homed = 1; \
  123. dcmotor##motID.VolVars.end = 1; \
  124. } else dcmotor##motID.VolVars.end = 0; \
  125. if(dcmotor##motID.Incr.incA != dcmotor##motID.Incr.lastA) { \
  126. dcmotor##motID.Incr.lastA = dcmotor##motID.Incr.incA; \
  127. dcmotor##motID.VolVars.IncDeltaT -= dcmotor##motID.VolVars.lastIncTime; \
  128. dcmotor##motID.VolVars.lastIncTime = timeISR(); \
  129. dcmotor##motID.VolVars.IncDeltaT += timeISR(); \
  130. dcmotor##motID.Incr.incB = digitalRead(MOT##motID##_B); \
  131. if(dcmotor##motID.VolVars.direction) dcmotor##motID.VolVars.Position++; \
  132. else dcmotor##motID.VolVars.Position--; \
  133. } \
  134. } while(0)
  135. #define DCMOTOR_CAPTURE_SERVICE_SINGLE(motID) CALL_FUN(DCMOTOR_CAPTURE_SERVICE_SINGLE_,motID)
  136. #define DCMOTOR_INIT_(motID) do{\
  137. digitalClear(M##motID##1);\
  138. digitalClear(M##motID##2);\
  139. digitalSet(M##motID##EN);\
  140. digitalSet(M##motID##EN2);\
  141. pinModeDigitalOut(M##motID##1);\
  142. pinModeDigitalOut(M##motID##2);\
  143. pinModeDigitalOut(M##motID##EN);\
  144. pinModeDigitalOut(M##motID##EN2);\
  145. \
  146. pinModeDigitalIn(MOT##motID##_END);\
  147. pinModeDigitalIn(MOT##motID##_A);\
  148. pinModeDigitalIn(MOT##motID##_B);\
  149. INIT_PWM(MOT##motID##_PWM);\
  150. SET_PWM(MOT##motID##_PWM, 0);\
  151. MOT##motID##_CONFIG();\
  152. \
  153. dcmotor##motID.Setting.Mode = 0;\
  154. dcmotor##motID.Setting.PosWindow = 2;\
  155. dcmotor##motID.Setting.PwmMin = 10;\
  156. dcmotor##motID.Setting.StallTime = 16;\
  157. dcmotor##motID.Setting.PosErrorGain = 7;\
  158. dcmotor##motID.Setting.reversed = 0;\
  159. dcmotor##motID.Setting.onlyPositive = 1;\
  160. \
  161. rampInit(&dcmotor##motID.PosRamp);\
  162. pidInit(&dcmotor##motID.SpeedPID);\
  163. pidInit(&dcmotor##motID.PosPID);\
  164. \
  165. dcmotor##motID.VolVars.Position = 0;\
  166. dcmotor##motID.VolVars.homed = 0;\
  167. dcmotor##motID.VolVars.end = 0;\
  168. dcmotor##motID.Vars.PWMConsign = dcmotor##motID.Vars.SpeedConsign = 0;\
  169. dcmotor##motID.Vars.lastPosition = 0;\
  170. } while(0)
  171. #define dcmotorInit(motID) CALL_FUN(DCMOTOR_INIT_,motID)
  172. #define DCMOTOR_LOAD_dcmotorVolVars_(motID) do{ \
  173. __critical {\
  174. dcmotorVolVars.lastIncTime = dcmotor##motID.VolVars.lastIncTime;\
  175. dcmotorVolVars.IncDeltaT = dcmotor##motID.VolVars.IncDeltaT;\
  176. dcmotorVolVars.Position = dcmotor##motID.VolVars.Position;\
  177. dcmotorVolVars.flags = dcmotor##motID.VolVars.flags;\
  178. dcmotor##motID.VolVars.IncDeltaT = 0;\
  179. }\
  180. } while(0)
  181. void dcmotorCompute(t_dcmotor *mot);
  182. #define DCMOTOR_FORMATPWM(motID) do{ \
  183. dcmotor_v = dcmotor##motID.Vars.PWMConsign; \
  184. if(dcmotor_v > 1023) dcmotor_v = 1023; \
  185. if(dcmotor_v < -1023) dcmotor_v = -1023; \
  186. if((dcmotor_v > 0) && (dcmotor_v < dcmotor##motID.Setting.PwmMin)) dcmotor_v = 0; \
  187. if((dcmotor_v < 0) && (dcmotor_v > -dcmotor##motID.Setting.PwmMin)) dcmotor_v = 0; \
  188. if(dcmotor##motID.Setting.onlyPositive && dcmotor##motID.VolVars.end && (dcmotor_v < 0)) dcmotor_v = 0;\
  189. /*dcmotor_v = (dcmotor##motID.Setting.reversed ? -dcmotor_v : dcmotor_v);*/\
  190. } while(0)
  191. #define DCMOTOR_UPDATE_ASYM_(motID) do{ \
  192. DCMOTOR_FORMATPWM(motID);\
  193. dcmotor_vabs = dcmotor_v < 0 ? 1023 + dcmotor_v : dcmotor_v; \
  194. SET_PWM(MOT##motID##_PWM, dcmotor_vabs); \
  195. if(dcmotor_v < 0) { digitalSet(M##motID##2);}\
  196. else { digitalClear(M##motID##2);}\
  197. } while(0)
  198. #define DCMOTOR_UPDATE_ASYM(motID) CALL_FUN(DCMOTOR_UPDATE_ASYM_,motID)
  199. #define DCMOTOR_UPDATE_SYM_(motID) do{ \
  200. DCMOTOR_FORMATPWM(motID);\
  201. dcmotor_vabs = dcmotor_v < 0 ? -dcmotor_v : dcmotor_v; \
  202. SET_PWM(MOT##motID##_PWM, dcmotor_vabs); \
  203. if(dcmotor_v < 0) { digitalClear(M##motID##1);digitalSet(M##motID##2);}\
  204. else { digitalClear(M##motID##2); digitalSet(M##motID##1);}\
  205. } while(0)
  206. #define DCMOTOR_UPDATE_SYM(motID) CALL_FUN(DCMOTOR_UPDATE_SYM_,motID)
  207. #define DCMOTOR_COMPUTE(motID, mode) do{\
  208. DCMOTOR_LOAD_dcmotorVolVars_(motID);\
  209. dcmotorCompute(&dcmotor##motID);\
  210. DCMOTOR_UPDATE_##mode(motID);\
  211. } while(0)
  212. #define DCMOTOR_SETDIR_(motID) do{ \
  213. if(dcmotor_v < 0) dcmotor##motID.VolVars.direction = 0;\
  214. else dcmotor##motID.VolVars.direction = 1;\
  215. } while(0)
  216. #define DCMOTOR_COMPUTE_SINGLE(motID, mode) do{\
  217. DCMOTOR_COMPUTE(motID, mode);\
  218. DCMOTOR_SETDIR_(motID);\
  219. } while(0)
  220. void dcmotorInput(t_dcmotor *mot);
  221. #define DCMOTOR_INPUT(motID) dcmotorInput(&dcmotor##motID)
  222. void dcmotorDeclareEE(t_dcmotor *mot);
  223. #define DCMOTOR_DECLARE_EE(motID) do{ dcmotorDeclareEE(&dcmotor##motID);} while(0)
  224. #define DCMOTOR(motID) (dcmotor##motID)
  225. #define DCMOTOR_GETPOS(motID) (DCMOTOR(motID).VolVars.Position)
  226. #endif // _DCMOTOR_H_