From d0ecad387792da2a48fca16a7d60a8ef55c2d766 Mon Sep 17 00:00:00 2001 From: Edward Emelianov Date: Wed, 17 Nov 2021 00:08:02 +0300 Subject: [PATCH] add servo-emulation @ stepper motors --- F0-nolib/3steppersLB/commonproto.c | 2 +- F0-nolib/3steppersLB/flash.c | 8 +- F0-nolib/3steppersLB/flash.h | 1 + F0-nolib/3steppersLB/hardware.c | 7 +- F0-nolib/3steppersLB/steppers.bin | Bin 22796 -> 23396 bytes F0-nolib/3steppersLB/steppers.c | 176 ++++++++++++++++++----------- F0-nolib/3steppersLB/steppers.h | 2 +- F0-nolib/3steppersLB/version.inc | 4 +- 8 files changed, 119 insertions(+), 81 deletions(-) diff --git a/F0-nolib/3steppersLB/commonproto.c b/F0-nolib/3steppersLB/commonproto.c index b7cb621..bd8a57e 100644 --- a/F0-nolib/3steppersLB/commonproto.c +++ b/F0-nolib/3steppersLB/commonproto.c @@ -53,7 +53,7 @@ static errcodes buzzerparser(uint8_t par, int32_t *val){ static errcodes adcparser(uint8_t par, int32_t *val){ uint8_t n = PARBASE(par); - if(n > NUMBER_OF_ADC_CHANNELS) return ERR_BADPAR; + if(n > NUMBER_OF_ADC_CHANNELS-1) return ERR_BADPAR; *val = (int32_t) getADCval(n); return ERR_OK; } diff --git a/F0-nolib/3steppersLB/flash.c b/F0-nolib/3steppersLB/flash.c index 2d9e7a4..b9ff680 100644 --- a/F0-nolib/3steppersLB/flash.c +++ b/F0-nolib/3steppersLB/flash.c @@ -34,7 +34,7 @@ static const uint32_t blocksize = (uint32_t)&_BLOCKSIZE; // max amount of Config records stored (will be recalculate in flashstorage_init() static uint32_t maxCnum = 1024 / sizeof(user_conf); // can't use blocksize here -#define DEFMF {.haveencoder = 1, .donthold = 1, .eswinv = 1} +#define DEFMF {.haveencoder = 1, .donthold = 1, .eswinv = 1, .keeppos = 1} #define USERCONF_INITIALIZER { \ .userconf_sz = sizeof(user_conf) \ @@ -42,12 +42,12 @@ static uint32_t maxCnum = 1024 / sizeof(user_conf); // can't use blocksize here ,.CANID = 0xaa \ ,.microsteps = {32, 32, 32} \ ,.accel = {500, 500, 500} \ - ,.maxspd = {3000, 3000, 3000} \ + ,.maxspd = {2000, 2000, 2000} \ ,.minspd = {20, 20, 20} \ ,.maxsteps = {500000, 500000, 500000} \ ,.encrev = {4000,4000,4000} \ - ,.encperstepmin = {5,5,5} \ - ,.encperstepmax = {50,50,50} \ + ,.encperstepmin = {17,17,17} \ + ,.encperstepmax = {23,23,23} \ ,.motflags = {DEFMF,DEFMF,DEFMF} \ ,.ESW_reaction = {ESW_ANYSTOP, ESW_ANYSTOP, ESW_ANYSTOP} \ } diff --git a/F0-nolib/3steppersLB/flash.h b/F0-nolib/3steppersLB/flash.h index aa9cc53..7eccc72 100644 --- a/F0-nolib/3steppersLB/flash.h +++ b/F0-nolib/3steppersLB/flash.h @@ -51,6 +51,7 @@ typedef struct{ uint8_t haveencoder : 1; // bit2 - have encoder uint8_t donthold : 1; // bit3 - clear power @ stop (don't hold motor when stopped) uint8_t eswinv : 1; // bit4 - invers end-switches + uint8_t keeppos : 1; // bit5 - keep current position (as servo motor) } motflags_t; /* diff --git a/F0-nolib/3steppersLB/hardware.c b/F0-nolib/3steppersLB/hardware.c index 1cbee6a..91c19e5 100644 --- a/F0-nolib/3steppersLB/hardware.c +++ b/F0-nolib/3steppersLB/hardware.c @@ -94,13 +94,11 @@ static void setup_mpwm(int i){ #error "change the code!" #endif TIM->CCR1 = MOTORTIM_ARRMIN - 3; // ~10us for pulse duration - TIM->CNT = 0; TIM->ARR = 0xffff; // TIM->EGR = TIM_EGR_UG; // generate update to refresh ARR TIM->BDTR |= TIM_BDTR_MOE; // enable main output TIM->CCER = TIM_CCER_CC1E; // turn it on, active high TIM->DIER = TIM_DIER_CC1IE; // allow CC interrupt (we should count steps) - //TIM->CR1 = TIM_CR1_CEN; NVIC_EnableIRQ(motirqs[i]); } @@ -124,7 +122,6 @@ static void setup_enc(int i){ TIM->ARR = the_conf.encrev[i]; // enable timer TIM->CR1 = TIM_CR1_CKD_1 | TIM_CR1_CEN; /* (4) */ - TIM->CNT = 0; NVIC_EnableIRQ(encirqs[i]); } @@ -144,9 +141,9 @@ void timers_setup(){ for(int i = 0; i < MOTORSNO; ++i) setup_mpwm(i); for(int i = 0; i < MOTORSNO; ++i){ - //if(the_conf.motflags[i].haveencoder){ // motor have the encoder + if(the_conf.motflags[i].haveencoder){ // motor have the encoder setup_enc(i); - //} + } } } diff --git a/F0-nolib/3steppersLB/steppers.bin b/F0-nolib/3steppersLB/steppers.bin index d307e48ff67116a5bb06d8c6f8eecedc7c5c525b..a22fdee4e8360ed5f9874fa1e72f68db73274256 100755 GIT binary patch delta 6573 zcmb7IeOy%6nLhW<00SZnLUb4qE)2zi0RlphC^o}@*I_R54VeKP-khEz{*Q};760%7*ruG-R(bjE1u|>fKo2+A^*}ciSGBeCD`ao3Yws9ohW`)tES7r# zeCR$O8z9?&$L~wK=Qr+eE9s0tt4iPgFq38Ted3pFCM$Zy<%-+vWc6s2GL&IgdPkRs ztYyrdz6g$$R{K~f-KQt4wAGhoW~C;dnP;Wg`Ao?5K9U_VPSW&MMX+!3_I*CzVE~bb5rEtKj+f7o5K|THkf1H1Sq?6oU zR$A-h;6Z?md59@|#dK?$=Qr`xYl)YY9`cIcR=vBdqMWGW2;qzj;i}XC|@I zEf3B48xJdudAKfC^2qx8(BJfkmEl=stn`T|8(lc(IkJ^RvC^c6cIdZMW2t`5vkLl2 z&(W<3;fY43I5f*Jl_ne}vsP9*;Yo$|!C)}3A8Ex%(*vAkv@K$i zVfP2bqR8Dzm4OmIj3^{apd?9S-eXFdYR`zhz~mJn?One(9;uIe%^xldnZCRvxfxPK zm^_6v=&P1nigl4%ig^7^X_;o=az9b35w*u;KgquJ z$XOxhjF)pR_vv3?q$=5}cKQloUN4&?WOJDBI?P7d%=qZ!$&sz|UOFTm?~xZ7DNnY3 zCnJ60Wu%Y1 z#UC8t5Ai?akMbU@fpc@ggzwW0 z^Em=ZJ;W#LhWIRjU1d*a(p;+3{w6qVY3#k|nA9Wj@IgO%C9f=nnG9sSGFbiIs_)GS~c0Q?z>7 zuG+9=7b~{#!(^GQj6c}g!5_4@kmBZX`(#@SzuexmIn}5n2aOSyI6ITCFnm67FJuxz zMt4hMW{igsnqZI+J(e=LN@jBQ5KqarYL7UTn9CB27_n08 ztiYfg!||5|t_D0~c@@u*JRxt>HQQy|7q%W!r#;LQL*bR5n<{6%v^A?;8iVCR4U=jR zwDktzvdth|0unSu`3bwG!`4o|+{&ct1^uQnqOH$pUM1+w@pXDZ+ocyS*XV_$W>&i7 zXGmU2x|w-+kJFTXi6Lo1vU%Eesg23Q^}#P0^>v<;`?Wuc@7SQ6`7HXsY>Dw5>cWI5 zOO)`(nqaE7ekrP5ifWhswc68@FSmW<78Blfw`ct6e0$18H|`1ClYj$=1B^fy=G5nl zbE^w_B%6a(41uKGB1aGf3FwDTrz@Sdp0PjkkMfoL27Y!dI7b3vWb)c1yT6tvI-^=` z=PcLzV;h2VKM9;kDeCKbftAk8iyg_<2P9NN{cr%C$lJk2aUyw@GYit)1>hOm$p3*~ zCG?FYv?xh5A%+bTEP@fYx|X;!oBNAM2EoI3{r z%S!XnY9gJMPtsF3@?HvPG1wmjiU^UmE@&XX8_0#+zOWqf@qobJa9XX~i1e?4SR@hn1JSQvTf9obV#A%#p7igntcW;^j1r>C6RhFZ!LX&1mTfLgq$S4cw5W$P#6T_&X>kdgzjMQYQ7gGa zgpaIC?6=*tvb#~D@uLGMjaBh~KzX;ayj4QUr!pGJa zh$g?8_?mW>nlS6;HPijwrKKCzUoJ$X;&5@v&7~p!)SnMMGC)`6`++>jp>l|$0}nzb zftSU6Hw)6O^9^g>gOjzl8#UpJ)-ZDgW0IA;%} zAtF_NdPAf^*KYQwAYr4w*G8mU{$$7{{$#-l?JIv0w6*?~vSyMyu0Y4<=9v`2#S8J4 zW?QXoxJ@H8*8Aqo#4G#?k4bNeO;2nT& zA*aCv+=CfPS2*1va5EP6k_%RwCOFp_6f<>6PU*f)mObKXIZ|D61Ui8C^B6Xc%o`@?9rJYmb^%Oc32@?YApm zC*3w?U3X2ltyo}0$isCt`Lk_gpXN$`q4{Y!|I^4H>Ks=bzyBa6x~FTiEIF0S9(^5W zeYdT&th*))E}Cs4*n5Wggv~CVWIlYQ+qQ)t!hOQTPp=3@?=}6fWcoxCA6xpTagzBl z8iA$4#Wo}f;qgtjqP*CyrxDC0yAr~b7qvpdoiMkO)Of+EHESD)w0ZvS@agC2_R}!$ zz<9Cp2qn+I=~kH)4L^5x+uGzxH}ccb=U2REszarxSgg_Om$N&kC$~7J)g7AQkj7S!CkSEWz*J&$3zH8CPbNP24!4Aqp`# zw=+QW`4jALGauJ);(aO0sDI+pGS1-x1J+Vj;yui8nl^S{*ufDKnK^Y;;9olt-*=3> zBWxoVnnuk^k(EC5FhuEk+Z+W2akuqxX#K^B ze-dsqVnd!;f3=nug=0i1q8B#NbY}XM*#V(hUbaoxT0fYj)qiJPVdx!a3?Cr|3h_BX zF{C9&$%J)vUU2SR_#+d#tD(Alr-SI$Io@{Pt?E-h(RWQWV{Z9Um=PMLpANXR*3tod z(u@UD_O(A>q6vHXkcmt$L5v0vqwmR0*(S$nn>hq=G9XSNuCBkv>6fz%=@i-*UgKN%P#k8&5Y7TdsB2p4&Hd1yPy|iIo{#63D-~DX?w@R!8x1U_Or90x?)GZ zqrshz3mO@(alg1IRk%s&rt+htsah!iUA4LV_tvJiwT=?^M!A`Fytb=MuJ7Y3a(zw{ zxt!rv>hc`|&kiT_8_ltOwD$>Jv3Bh5Ud7Ozovqiq7E9xGuhON#;;8WzL3`DUvF<0* zFTC_D*y1HpvsdAEg_6lfzjsL^nx05GTI2YK4=oSh`Z_R!Uc98juLk zmFveURY9g62d=fJJa?^@fB3%HMy?E8d(6#Z(!6v{fv~M}?7N0jxsTQ5ne%a^EkVeR zEglCK@iK&+#G4^#(0v-tOz1wR=T6*MIc^_$aLqwVeE&t+kwTX&J92yOIeObeFUNoO ztbijTJujF0XOwfv<U!?;+t3P z?+1=OD*h_BmfhkNqw;E#`_UJAWjhR(bAhF?Kkys*zA;7bfcTr-*wMkf-E3xc9qz;c zeP}xjeu=z93Q(~bFhYL^m<5#eqlE>bjFy9(1sq>=tb{xR`FibW<3p8-!Wne(rzra# zKr6luz6l&a$2{QE071Cyz-eF#m}wZjT=Yvt#0%?)>I>lPy3xVne^DmIH4&9UflpL$ z5wIN?0t$eew$Y}NLWbQ`A`Y5n;zoQ6SPkSWGJ6KSCcsG3=-$%5D6|LApds2Q;4ttG za2hyc8GUMFE#s`llh#)eh& zauc4DAxDBWKsjU%oCR!vp8~KE*bLbWZUG)&LYyi)gzeOzMgzdl0OgPmfR6#Mpul_J zDc}<1&%yK^<5Dyx8koLk#7Ck6Fn!l}9I_ou-#5Os6n?<(0GA-20@F8-hA4~%SX0%4 zM{y_|9zN*f$5)W8U~L^KY*3v~w67;5i!1ByajXY-J32c%kb>djva_=}uCBhMq9Wyw+LKfHB-j1a1o=yjH6l2A0 z{qA?=irc$dpV-og2GPRYcX#f1oTHWX?4U%r_V4e!=ky8MHu2Y0d9jZ@vD&*EU+ z+Ou`X6YEFktLE95yu1R=$gR#@otK@5|7#*f!|L)FC!OaT3Nf#-EQytz(7zS( NUvY7<_+#t${|^L_v={&Y delta 6046 zcmb7Idwf*&l|R2b0VW}k$pbQ(#BfOvCz%BEG9(aj^14jshCB&O641%Z28uWfQ3Kje zuvim(A=he>K}D-=v}{YsVy!E}$6A+dZFd56n-FNn+I4KJ-CLKMnam`!-`_>W?th!f zcfRNR&hK&Vxxe#!%pYH4kDg=(vXWR@N%~uWeBjCWR5x*jKL6wL3#MyEUg7_PZ+zZv z2>hL|^idAE1=#VGvg`dO{o^1#F{FQ}{Ks!)3qo#C`LmEMJQh%v>pm0C)r~KWTF8Xt z!1(e7>zM71V2miJIYB`cgJu%cu3(N$P&Wr{lAtb`&4yeTq}&)Utuoh_z`ik0Q7Bz}1bUALt=#+D2vdqCXUWE0DRLGRR`^z9OBF zmeFd;>lf6bpoku-VPm(j;%6(aPD|1ziTAobAgDJ7lnwgV60GPciAc0E606X&*QP9t z&Q53QUn4OhQ~x!>)E`B}UZ#Gk>EqD9A5rR}bE=s7?~z;^Q{Rn@?VzPh{dFW8+8M41 zTz@xm6ZD@%ey}4oI?c+;7UozcSIIAt&%xB=kqp>gi70PHoAgZGiC%AyD8A^NEleGV zyzftd^?}HgKOWp4ned;L%HSV$ll36{JqEl3Tm}L_HxLWo2L=X+41zThiOdb4EDvRA zK$2~|Gv*=_z8zLdV)v)p!sXH;(y3M9@^qu^Kt=jwS61Q$mS2Lh6CuSLYfkcnqUGU= zKToNCMkU1Zb?T9j61!wu`X`}lZT}Q1PfteMG_;NXylqQJ`Sy}kNflb#kEj0jW!ut_ z^45}q^jAX3H48At%V?W~w#(6WG1{6@79UcUE;S}aX>C89x{9`DZQRhTvTo^T@l0(B zq>r^0<|$9|uJziH6f>C3mLbl+MaT!J?Zq!ak*ZBQ9m}k$?g9xqe!C zAuc7k|4V%+5cD%~#&0-9>UWfhxV7w0O0=OTts#tI)z)wx0&fqCl$XcUop2rL%j}92zwWkcZp0E3qbyNyBr;pNW5%CG`as%0}mTzuq2WOLSIc=+u;e(v}#G64bv$ zl(wXI+<~BZkg04o8-BeVe6W^Q^OyvKw?cmdHfJT~D{_yiqdxx0%h-R$~Hp40RKFus?=E|V?5RyeR-x}Nm^G?mW zRdQtj;6hIEV zHxpS=g1N|diYhQj+zgHdcZ2yd*9RT|27!P~da;)DHlQEy0f$k36gUo8Ht2zO*7nr_oM zby6dsjQYGd;6ko3Q11o>~{Qm0!Q&01il5EWS62cOR5T(^4aPO1v zzyTs1V#frcVc2-sjP=SlQw|CGdL_nG(5)gUywq@tiKGsMDTB$T4#R1z&{ixcD7*K1 znU$eTK-sSAWmUY4*Lx?-7q4smy!E-v>%JaVj+rjHe-et!M9(wz?#Qe-Kl5~We&)GZ zLWU1ycJ6GCO04YajLhWDZ$tiWlScs$Fd}WMZtV^JBLWM zMraK-?HjEUso$J;ZfCcUS{(Vy$>%EmJ{be=tL8~9!GLM#_`(Dqq**fd3Ti=MLHduq zT&`+ixx$35-)$-OVhM{V+tS)rH-+!>-+)1~(fqG-1O60jK{UDB-z>2bqf@ss8L3el zQ7)(D30F5NOK&i_t$1a}u`!C^Dj;xbt5hxhPO6i9r`qcm(0XG@Vd}oNMRak{=dd3n zL#xA{(CS%4zj@f#yz{KFMcz_lYV}A@Ne`M1OO;ZyeMmYYMYkrjZZVNXxYQ-3nuaA> zLzf;mMX$N@O1oril;xCGK|LSBW4Ie-6j;bu*iN%;dnzlcqb`Sx(}Q~}E34ZsRp3!x zp5rn4;hYun^K*Gb>ew8Q(2hA$x6hT?6Z=`=^vOh5v87=$n@Z)~O*AZd z+TUnv*QcZ@6=fHOP8Q<0^bB4nqm=S|8!J6f;l3F=sO7@Va;`14b*hu)3+mjgEKORm zW;a{pw(UZ8hBq5Scg~@toz$J$;1&$NVh&T+N8p>)KkT{A^{iY_zquP-dcw)U|G{yC`%Q2n*trpXWr8KqAkY2Jkk(1(*RF zUQYw?F<#do^jLsaT_v7*JOg{7_rbmk?9g82@1(7Gk=1yWk(rmmW;v_QBW1~1^`rQv zRU`OTdec{@&(AhtO|TjaPSO6+U}8&TrhM+)%94TJ#{~7xS><@TW7!{(uY64I2ltVW zVN+68+~oekTVAT3dRG!tN+txlK~5@YB9HNo!8|G@LERf#lAb-Cf>YeE z^nt@zzrE9F+nf49BdK?W`P)sLTZV8uafl#w$y_4jws0kCI(CxU5jH??3j10~jo?T@ zYFc%eR6`ht1+3%h>0hOs_mdd#^H6Yyco?~ZD#8&4^bMpp0D?R~KXZ_{*y-BH!>fF} zGR>`?sz$VU%zUTz$V(|@+qX_EfR~g--dBAO-mts=2)$uU9P$pPM(HZYE9lZQzV-_6 z6~)&pAEyy1wH4aLqrN-k6xW?{dZS0`kxi{VnC|yuA5Yzfw7K}OPu_XK)M4+mC1UQI zT03M@qh@vQn_e^>M~aMYnDRd+>;%Y>27J52%@SGY@;$z-b%m{M)KuL&&6_q$?FNsr z*-j&gjZaD}qfu^aX~ckya%wA_p19Aabk-waKMEo15VH30CTL?w0IqEg+o8P>%7grB z2wNhlUk{ObM@Z6gsM0yydVxmr38L=A^^{RhFAzWTBO=Co-TpQyq4k34 z8Gl!n_k7pNU;CNIlbTvr(Ar2N70WNRBQ8g!&Z=aYMof*7j1g%$o_D#t+@6ZnhO%_t z(T+jC((!HoXy-w{U5anL6nEa(WH@B{uP^5Vf7d*H9sqwaae0~zVs32VxrTd(m;~5> zUQC`z%=^PI9s^DQJO{p-b36xmZuFt<7&=w~9HZq2>4Kxx7@7I)ys{xP-R(LRg@f$2 z(5f0T$9NZ~+*X*{&n%^0oV6!JIdv;5EcULjby8y6V@6i^$)M+CV$-t~Si3Yzx%9+Zbp3d%Lt@7G+v-=uz;bLnpD9>sybt)>Fy$s3zLVXhk(mv1WNx0& zWm;VBLf742R@&)rlzk^n#48r$M`o}qnynK;W}$1lpTEyWEhd}%HkrFwa-~{+kpzVu z@i^>KLa%}a^fv$Z&>J7H%3o3QA~iRZ)jZO$uI7-VxwFu<&R;6?C^4*wrrx!@7q?~T z@)u7_S498ASS;wmZfvx>G$|HRjDI0KWu8Kp$)ELqhrF`Tf0uv#fG+bUn*|&2UjrhZ z)9b)ftHWA6PT^ShN}zP`w;!$_5HeS2wWb5f=x5j=D7UdAq#g_|M-V3hJcyS9Jcu4N zdIF71NGHAwgaN*c@Z~`Scna~Qp;md)oNVGrW&D13Y!x0u(R^Tq!z5zY8d}!;i!-u zfS%Wgaq#0yE%*s~f-Zwq;3L?!fd_%(jpG%?3z_L0$}R#9fcJA8d=NO?Fy6VgPFL*3 zGuhy$6X5p4;HQ8RczF!G3m60Rc(z@@0C2E*{KIuW)WsYqCH)oPbm{nW8(xh{e{(D8 zbvhz1*asvzaBBlDLw;)O_??x-Oenuid9Lbm(y`DyUN3z@zH@j;0;(M2k5~UeXF3Rn z9tEBPhJi8Qb>L0g_@SC6=B~oe9G~D9zgloN@Hfc2z=J@_Vmui5IB*~yyA1d&umkcr z@MYjx$UblYXoXC;cE$oVkdyco6sTTIdNa5P*bcc2+yLCQnB4l!5S+kv0~`SN12vEj zf{y{uE`|f(_kbzLlVEOKz<2)7I+BqIq=88U68MWFXHJN zAxG7rFW?5qX?5epwdo7oRXw}AZpACf5v%t0xo)MseLXH$&z`+&x%`{G z<+ZgdQOC8XCwFgO$F5yD;$BxzPd9JZ-LtE&142w+$DXgD2iM(uc`?Ow_jL8_LhU_$ z*Yu9AE)?IieLL>njf&&VO(7w^bggI=3-Su`bMx_E97E%G zwB$24pQ5Ej2pSS-4EW?G1Py!+xMIdj0Q-P@@{u0kqAi%Nd59gj0a$V~QUlxzykNoE z1NH2Z>A0UFa$H^_mXAk9NYkWBMY5^T|f{G`oQmC z@Hxl_A@g8pe+p|(AOHH+t-9RT7xPaN@sIezqAzhQj(-*q{}gDSw6rwkzuWHlU-~xm AGXMYp diff --git a/F0-nolib/3steppersLB/steppers.c b/F0-nolib/3steppersLB/steppers.c index e9f0b57..c765262 100644 --- a/F0-nolib/3steppersLB/steppers.c +++ b/F0-nolib/3steppersLB/steppers.c @@ -42,19 +42,19 @@ static volatile int32_t stppos[MOTORSNO] = {0}; // previous position when check (set to current in start of moving) static int32_t prevstppos[MOTORSNO]; // target stepper position -static int32_t targstppos[MOTORSNO]; +static int32_t targstppos[MOTORSNO] = {0}; // position to start deceleration static int32_t decelstartpos[MOTORSNO]; // current encoder position (4 per ticks) (without TIM->CNT) static volatile int32_t encpos[MOTORSNO] = {0}; // previous encoder position -static int32_t prevencpos[MOTORSNO]; +static int32_t prevencpos[MOTORSNO] = {0}; // encoders' ticks per step (calculates @ init) static int32_t encperstep[MOTORSNO]; // current speed static uint16_t curspeed[MOTORSNO]; -static uint16_t decstartspeed[MOTORSNO]; // speed when deceleration starts +static uint16_t startspeed[MOTORSNO]; // speed when deceleration starts // ==1 to stop @ nearest step static uint8_t stopflag[MOTORSNO]; // motor state @@ -81,7 +81,6 @@ TRUE_INLINE void recalcARR(int i){ else if(ARR > 0xffff) ARR = 0xffff; mottimers[i]->ARR = ARR; curspeed[i] = (((PCLK/(MOTORTIM_PSC+1)) / (ARR+1)) >> ustepsshift[i]); // recalculate speed due to new val - //SEND("New ARR["); bufputchar('0'+i); SEND("]="); printu(ARR); NL(); } // run this function after each steppers parameters changing @@ -115,17 +114,22 @@ int setencpos(uint8_t i, int32_t position){ int32_t remain = position % the_conf.encrev[i]; if(remain < 0) remain += the_conf.encrev[i]; enctimers[i]->CNT = remain; - encpos[i] = position - remain; - SEND("position=");printi(position);SEND(", remain=");printi(remain);SEND(", CNT=");printu(enctimers[i]->CNT);SEND(", pos=");printi(encpos[i]);NL(); + prevencpos[i] = encpos[i] = position - remain; + SEND("MOTOR"); bufputchar('0'+i); SEND(", position="); printi(position); SEND(", remain="); + printi(remain); SEND(", CNT="); printu(enctimers[i]->CNT); SEND(", pos="); printi(encpos[i]); NL(); return TRUE; } // get current position errcodes getpos(uint8_t i, int32_t *position){ - /*if(the_conf.motflags[i].haveencoder){ - *position = encoder_position(i) / encperstep[i]; - }else */ - *position = stppos[i]; + if(the_conf.motflags[i].haveencoder){ + int32_t p = encoder_position(i); + if(p < 0) p -= encperstep[i]>>1; + else p += encperstep[i]>>1; + p /= encperstep[i]; + *position = p; + }else + *position = stppos[i]; return ERR_OK; } @@ -134,6 +138,35 @@ errcodes getremainsteps(uint8_t i, int32_t *position){ return ERR_OK; } +// calculate acceleration/deceleration parameters for motor i +static void calcacceleration(uint8_t i){ + int32_t delta = targstppos[i] - stppos[i]; + if(delta > 0){ // positive direction + if(delta > 2*(int32_t)accdecsteps[i]){ // can move by trapezoid + decelstartpos[i] = targstppos[i] - accdecsteps[i]; + }else{ // triangle speed profile + decelstartpos[i] = stppos[i] + delta/2; + } + motdir[i] = 1; + if(the_conf.motflags[i].reverse) MOTOR_CCW(i); + else MOTOR_CW(i); + }else{ // negative direction + delta = -delta; + if(delta > 2*(int32_t)accdecsteps[i]){ // can move by trapezoid + decelstartpos[i] = targstppos[i] + accdecsteps[i]; + }else{ // triangle speed profile + decelstartpos[i] = stppos[i] - delta/2; + } + motdir[i] = -1; + if(the_conf.motflags[i].reverse) MOTOR_CW(i); + else MOTOR_CCW(i); + } + state[i] = STP_ACCEL; + startspeed[i] = curspeed[i]; + Taccel[i] = Tms; + recalcARR(i); +} + // move to absolute position errcodes motor_absmove(uint8_t i, int32_t newpos){ //if(i >= MOTORSNO) return ERR_BADPAR; // bad motor number @@ -144,38 +177,14 @@ errcodes motor_absmove(uint8_t i, int32_t newpos){ targstppos[i] = newpos; prevencpos[i] = encoder_position(i); prevstppos[i] = stppos[i]; - uint8_t inv = the_conf.motflags[i].reverse; - int32_t delta = newpos - stppos[i]; - SEND("delta="); printi(delta); - if(delta > 0){ // positive direction - if(delta > 2*(int32_t)accdecsteps[i]){ // can move by trapezoid - decelstartpos[i] = targstppos[i] - accdecsteps[i]; - }else{ // triangle speed profile - decelstartpos[i] = stppos[i] + delta/2; - } - motdir[i] = 1; - if(inv) MOTOR_CCW(i); - else MOTOR_CW(i); - }else{ // negative direction - delta = -delta; - if(delta > 2*(int32_t)accdecsteps[i]){ // can move by trapezoid - decelstartpos[i] = targstppos[i] + accdecsteps[i]; - }else{ // triangle speed profile - decelstartpos[i] = stppos[i] - delta/2; - } - motdir[i] = -1; - if(inv) MOTOR_CW(i); - else MOTOR_CCW(i); - } - SEND("\ntargstppos="); printi(targstppos[i]); - SEND("\ndecelstart="); printi(decelstartpos[i]); - SEND("\naccdecsteps="); printu(accdecsteps[i]); NL(); curspeed[i] = the_conf.minspd[i]; - recalcARR(i); + calcacceleration(i); + SEND("MOTOR"); bufputchar('0'+i); + SEND(" targstppos="); printi(targstppos[i]); + SEND(", decelstart="); printi(decelstartpos[i]); + SEND(", accdecsteps="); printu(accdecsteps[i]); NL(); MOTOR_EN(i); mottimers[i]->CR1 |= TIM_CR1_CEN; // start timer - state[i] = STP_ACCEL; - Taccel[i] = Tms; return ERR_OK; } @@ -210,12 +219,24 @@ void addmicrostep(uint8_t i){ if(++microsteps[i] == the_conf.microsteps[i]){ microsteps[i] = 0; stppos[i] += motdir[i]; - if(stopflag[i] || stppos[i] == targstppos[i]){ // stop NOW + uint8_t stop_at_pos = 0; + if(motdir[i] > 0){ + if(stppos[i] >= targstppos[i]){ // reached start of deceleration + stop_at_pos = 1; + } + }else{ + if(stppos[i] <= targstppos[i]){ + stop_at_pos = 1; + } + } + if(stopflag[i] || stop_at_pos){ // stop NOW + if(stopflag[i]) targstppos[i] = stppos[i]; // keep position (for keep flag) stopflag[i] = 0; mottimers[i]->CR1 &= ~TIM_CR1_CEN; // stop timer if(the_conf.motflags[i].donthold) MOTOR_DIS(i); // turn off power state[i] = STP_RELAX; + SEND("MOTOR"); bufputchar('0'+i); SEND(" stop @"); printi(stppos[i]); newline(); } } } @@ -237,45 +258,76 @@ static t_stalled chkSTALL(uint8_t i){ if(!the_conf.motflags[i].haveencoder) return STALL_NO; int32_t curencpos = encoder_position(i), Denc = curencpos - prevencpos[i]; int32_t curstppos = stppos[i], Dstp = curstppos - prevstppos[i]; - if(Denc < 0) Denc = -Denc; - if(Dstp < 0) Dstp = -Dstp; + int difsign = 1; + if(Dstp < 0){ + Dstp = -Dstp; + difsign = -difsign; + } if(Dstp < 10){ // didn't move even @ 10 steps return STALL_NO; } + if(Denc < 0){ + Denc = -Denc; + difsign = -difsign; + } + if(difsign == -1){ // motor and encoder moves to different sides!!! + Denc = -Denc; // init STALL state + } prevencpos[i] = curencpos; - curstppos = curencpos / encperstep[i]; // recalculate current position + getpos(i, &curstppos); // recalculate current position stppos[i] = curstppos; prevstppos[i] = curstppos; if(Denc < the_conf.encperstepmin[i]*Dstp || the_conf.encperstepmax[i]*Dstp < Denc){ // stall? - SEND("Denc="); printu(Denc); SEND(", Dstp="); printu(Dstp); NL(); - if(++Nstalled >= NSTALLEDMAX){ + SEND("MOTOR"); bufputchar('0'+i); SEND(" Denc="); printi(Denc); SEND(", Dstp="); printu(Dstp); + SEND(", speed="); printu(curspeed[i]); + if(++Nstalled > NSTALLEDMAX){ stopflag[i] = 1; Nstalled = 0; - DBG("STALL!"); + SEND(" --- STALL!"); NL(); return STALL_STOP; }else{ uint16_t spd = curspeed[i] >> 1; // speed / 2 curspeed[i] = (spd > the_conf.minspd[i]) ? spd : the_conf.minspd[i]; - recalcARR(i); - if(state[i] == STP_MOVE) - state[i] = STP_ACCEL; - SEND("pre-stall, speed="); printu(curspeed[i]); NL(); + // now recalculate acc/dec parameters + calcacceleration(i); + SEND(" --- pre-stall, newspeed="); printu(curspeed[i]); NL(); return STALL_ONCE; } } + prevstppos[i] = curstppos; Nstalled = 0; return STALL_NO; } #define TODECEL() do{state[i] = STP_DECEL; \ - decstartspeed[i] = curspeed[i]; \ + startspeed[i] = curspeed[i]; \ Taccel[i] = Tms; \ - SEND(" -> DECEL@"); printi(stppos[i]); SEND(", V="); printu(curspeed[i]); NL();}while(0) + SEND("MOTOR"); bufputchar('0'+i); \ + SEND(" -> DECEL@"); printi(stppos[i]); SEND(", V="); printu(curspeed[i]); NL(); \ + }while(0) // check state of i`th stepper static void chkstepper(int i){ int32_t newspeed; switch(state[i]){ + case STP_RELAX: // check if need to keep current position + if(the_conf.motflags[i].haveencoder && the_conf.motflags[i].keeppos){ + getpos(i, &newspeed); + int32_t diff = stppos[i] - newspeed; // correct `curpos` counter by encoder + if(diff){ + SEND("MOTOR"); bufputchar('0'+i); + SEND(" diff="); printi(diff); + SEND(", change stppos from "); printi(stppos[i]); SEND(" to "); printi(newspeed); NL(); + stppos[i] = newspeed; + } + diff = targstppos[i] - newspeed; // check whether we need to change position + if(diff){ // try to correct position + SEND("MOTOR"); bufputchar('0'+i); + SEND(" curpos="); printi(newspeed); SEND(", need="); printi(targstppos[i]); NL(); + motor_absmove(i, targstppos[i]); + } + } + break; case STP_ACCEL: // acceleration to max speed if(STALL_NO == chkSTALL(i)){ //newspeed = curspeed[i] + dV[i]; @@ -283,6 +335,7 @@ static void chkstepper(int i){ if(newspeed >= the_conf.maxspd[i]){ // max speed reached -> move with it curspeed[i] = the_conf.maxspd[i]; state[i] = STP_MOVE; + SEND("MOTOR"); bufputchar('0'+i); SEND(" -> MOVE@"); printi(stppos[i]); SEND(", V="); printu(curspeed[i]); NL(); }else{ // increase speed curspeed[i] = newspeed; @@ -317,33 +370,20 @@ static void chkstepper(int i){ case STP_DECEL: if(STALL_NO == chkSTALL(i)){ //newspeed = curspeed[i] - dV[i]; - newspeed = decstartspeed[i] - (the_conf.accel[i] * (Tms - Taccel[i])) / 1000; + newspeed = startspeed[i] - (the_conf.accel[i] * (Tms - Taccel[i])) / 1000; if(newspeed > the_conf.minspd[i]){ curspeed[i] = newspeed; }else{ curspeed[i] = the_conf.minspd[i]; state[i] = STP_MVSLOW; + SEND("MOTOR"); bufputchar('0'+i); SEND(" -> MVSLOW@"); printi(stppos[i]); NL(); } recalcARR(i); //SEND("spd="); printu(curspeed[i]); SEND(", pos="); printi(stppos[i]); newline(); } - // fallthrough - case STP_MVSLOW: // position check is in add_microstep - /* - if(motdir[i] > 0){ - if(stppos[i] >= targstppos[i]){ // reached start of deceleration - stopflag[i] = 0; - SEND(" -> STOP@"); printi(stppos[i]); NL(); - } - }else{ - if(stppos[i] <= targstppos[i]){ - stopflag[i] = 0; - SEND(" -> STOP@"); printi(stppos[i]); NL(); - } - }*/ break; - default: // RELAX, STALL, ERR -> do nothing + default: // STP_MVSLOW, STALL, ERR -> do nothing return; } switch(mvzerostate[i]){ diff --git a/F0-nolib/3steppersLB/steppers.h b/F0-nolib/3steppersLB/steppers.h index d313e7f..a710191 100644 --- a/F0-nolib/3steppersLB/steppers.h +++ b/F0-nolib/3steppersLB/steppers.h @@ -24,7 +24,7 @@ #include "commonproto.h" // amount of tries to detect motor stall -#define NSTALLEDMAX (55) +#define NSTALLEDMAX (5) // stepper states typedef enum{ diff --git a/F0-nolib/3steppersLB/version.inc b/F0-nolib/3steppersLB/version.inc index d76b5ec..66444c1 100644 --- a/F0-nolib/3steppersLB/version.inc +++ b/F0-nolib/3steppersLB/version.inc @@ -1,2 +1,2 @@ -#define BUILD_NUMBER "97" -#define BUILD_DATE "2021-11-16" +#define BUILD_NUMBER "114" +#define BUILD_DATE "2021-11-17"