gin66 / FastAccelStepper

A high speed stepper library for Atmega 168/328p (nano), Atmega32u4, Atmega 2560, ESP32, ESP32S2, ESP32S3, ESP32C3, ESP32C6 and Atmel SAM Due
MIT License
311 stars 71 forks source link

How high can the control frequency be on the esp32 using this library? #288

Open programmeddeath1 opened 4 days ago

programmeddeath1 commented 4 days ago

I have a esp32 controlling 3 AC Servo motors of a delta robot with a maximum RPM of 3000 and an entire motion plan sent to the esp32 over UDP at a rate 1.12ms per message.

I am trying to execute motions on the esp32 using FastAccelStepper at two different control cycles - 0.02 (ie a point every 20ms) and 0.015( a point every 15ms) run at a max velocity of 1500 RPM. The motion plan for the two control cycles for the same positions is as follows -

CC = 0.02
total points :  47
POINT: 
 positions: [0.26831230272552986, 0.26831230272552986, 0.0029724586491534327]
velocities: [-0.5669126948666714, -0.5669126948666714, 0.07275552637463709]
accelerations: [-21.37, -21.37, 0.0]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs:  26528437
Count :  0
POINT: 
 positions: [0.24575334131226417, 0.24575334131226417, 0.004902549033968065]
velocities: [-1.1338253897333428, -1.1338253897333428, 0.07275552637463709]
accelerations: [-21.37, -21.37, 0.0]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs:  53056874
Count :  1
POINT: 
 positions: [0.21191489919236567, 0.21191489919236567, 0.0068326394187826975]
velocities: [-1.133825389733343, -1.133825389733343, 0.07275552637463709]
accelerations: [21.37, 21.37, 0.0]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs:  79585310
Count :  2
POINT: 
 positions: [0.18935593777909998, 0.18935593777909998, 0.00876272980359733]
velocities: [-0.5669126948666715, -0.5669126948666715, 0.07275552637463709]
accelerations: [21.37, 21.37, 0.0]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 106113747
Count :  3
POINT: 
 positions: [0.1818362839746781, 0.1818362839746781, 0.010568969776197397]
velocities: [0.0, 0.0, 0.0]
accelerations: [0.0, 0.0, 0.0]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 132642184
Count :  4
POINT: 
 positions: [0.17382536889095124, 0.17382536889095124, 0.017967653621135504]
velocities: [-0.5851380270316452, -0.5851380270316452, 0.42337658803633726]
accelerations: [-21.37, -21.37, 0.0]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 160023468
Count :  5
POINT: 
 positions: [0.14979262363977064, 0.14979262363977064, 0.02956024797841075]
velocities: [-1.1702760540632904, -1.1702760540632904, 0.42337658803633726]
accelerations: [21.37, 21.37, 0.0]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 187404751
Count :  6
POINT: 
 positions: [0.12575987838859004, 0.12575987838859004, 0.041152842335686]
velocities: [-0.5851380270316451, -0.5851380270316451, 0.42337658803633726]
accelerations: [21.37, 21.37, 0.0]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 214786034
Count :  7
POINT: 
 positions: [0.11774896330486317, 0.11774896330486317, 0.04855152618062408]
velocities: [0.0, 0.0, 0.0]
accelerations: [0.0, 0.0, 0.0]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 242167318
Count :  8
POINT: 
 positions: [0.11079022865783808, 0.11079022865783808, 0.05582936936414794]
velocities: [-0.44093822540279076, -0.44093822540279076, 0.557723065386227]
accelerations: [0.0, 0.0, 21.37]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 268265730
Count :  9
POINT: 
 positions: [0.09928244116520318, 0.09928244116520318, 0.0776628989147195]
velocities: [-0.44093822540279076, -0.44093822540279076, 1.115446130772454]
accelerations: [0.0, 0.0, -21.37]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 294364142
Count :  10
POINT: 
 positions: [0.0877746536725683, 0.0877746536725683, 0.09949642846529107]
velocities: [-0.44093822540279076, -0.44093822540279076, 0.5577230653862271]
accelerations: [0.0, 0.0, -21.37]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 320462554
Count :  11
POINT: 
 positions: [0.0808159190255432, 0.0808159190255432, 0.10677427164881492]
velocities: [1.1102230246251565e-16, 1.1102230246251565e-16, 0.0]
accelerations: [0.0, 0.0, 0.0]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 346560966
Count :  12
POINT: 
 positions: [0.0788156519159068, 0.0788156519159068, 0.11612888723980719]
velocities: [-0.07166344670845368, -0.07166344670845368, 0.6323102643157151]
accelerations: [0.0, 0.0, 21.37]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 376149654
Count :  13
POINT: 
 positions: [0.07669522454435801, 0.07669522454435801, 0.14419273401278399]
velocities: [-0.07166344670845368, -0.07166344670845368, 1.2646205286314303]
accelerations: [0.0, 0.0, -21.37]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 405738342
Count :  14
POINT: 
 positions: [0.07457479717280922, 0.07457479717280922, 0.17225658078576078]
velocities: [-0.07166344670845368, -0.07166344670845368, 0.6323102643157151]
accelerations: [0.0, 0.0, -21.37]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 435327030
Count :  15
POINT: 
 positions: [0.07257453006317283, 0.07257453006317283, 0.18161119637675305]
velocities: [-1.3877787807814457e-16, -1.3877787807814457e-16, 0.0]
accelerations: [0.0, 0.0, 0.0]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 464915718
Count :  16
POINT: 
 positions: [0.07257453006317283, 0.07257453006317283, 0.18161119637675305]
velocities: [0.0, 0.0, 0.0]
accelerations: [0.0, 0.0, 0.0]
effort: [0.0]
time_from_start: 
  secs: 1
  nsecs: 365237339
Count :  17
POINT: 
 positions: [0.0795875587214206, 0.0795875587214206, 0.18862422503500081]
velocities: [0.5474822781182189, 0.5474822781182189, 0.5474822781182189]
accelerations: [21.37, 21.37, 21.37]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 390856538
Count :  18
POINT: 
 positions: [0.10062664469616427, 0.10062664469616427, 0.20581985228212318]
velocities: [1.0949645562364378, 1.0949645562364378, 0.6896629080550688]
accelerations: [21.37, 21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 416475737
Count :  19
POINT: 
 positions: [0.13218527365827978, 0.13218527365827978, 0.22348846342089834]
velocities: [1.0949645562364376, 1.0949645562364376, 0.6896629080550688]
accelerations: [-21.37, -21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 442094936
Count :  20
POINT: 
 positions: [0.15322435963302344, 0.15322435963302344, 0.2406840906680207]
velocities: [0.5474822781182188, 0.5474822781182188, 0.5474822781182187]
accelerations: [-21.37, -21.37, -21.37]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 467714135
Count :  21
POINT: 
 positions: [0.16023738829127132, 0.16023738829127132, 0.2476971193262686]
velocities: [0.0, 0.0, -1.1102230246251565e-16]
accelerations: [0.0, 0.0, 0.0]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 493333333
Count :  22
POINT: 
 positions: [0.16023738829127132, 0.16023738829127132, 0.2476971193262686]
velocities: [0.0, 0.0, 0.0]
accelerations: [0.0, 0.0, 0.0]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 593333333
Count :  23
POINT: 
 positions: [0.15322435963302344, 0.15322435963302344, 0.2406840906680207]
velocities: [-0.5474822781182189, -0.5474822781182189, -0.5474822781182189]
accelerations: [-21.37, -21.37, -21.37]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 618952532
Count :  24
POINT: 
 positions: [0.13218527365827976, 0.13218527365827976, 0.22348846342089834]
velocities: [-1.0949645562364378, -1.0949645562364378, -0.6896629080550688]
accelerations: [-21.37, -21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 644571731
Count :  25
POINT: 
 positions: [0.10062664469616427, 0.10062664469616427, 0.20581985228212318]
velocities: [-1.0949645562364376, -1.0949645562364376, -0.6896629080550688]
accelerations: [21.37, 21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 670190930
Count :  26
POINT: 
 positions: [0.0795875587214206, 0.0795875587214206, 0.18862422503500081]
velocities: [-0.5474822781182188, -0.5474822781182188, -0.5474822781182187]
accelerations: [21.37, 21.37, 21.37]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 695810128
Count :  27
POINT: 
 positions: [0.07257453006317272, 0.07257453006317272, 0.18161119637675294]
velocities: [0.0, 0.0, 1.1102230246251565e-16]
accelerations: [0.0, 0.0, 0.0]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 721429327
Count :  28
POINT: 
 positions: [0.07457479717280914, 0.07457479717280914, 0.17225658078576067]
velocities: [0.07166344670845488, 0.07166344670845488, -0.6323102643157147]
accelerations: [0.0, 0.0, -21.37]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 751018015
Count :  29
POINT: 
 positions: [0.07669522454435795, 0.07669522454435795, 0.14419273401278393]
velocities: [0.07166344670845488, 0.07166344670845488, -1.2646205286314294]
accelerations: [0.0, 0.0, 21.37]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 780606703
Count :  30
POINT: 
 positions: [0.07881565191590678, 0.07881565191590678, 0.11612888723980717]
velocities: [0.07166344670845488, 0.07166344670845488, -0.6323102643157149]
accelerations: [0.0, 0.0, 21.37]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 810195392
Count :  31
POINT: 
 positions: [0.0808159190255432, 0.0808159190255432, 0.10677427164881492]
velocities: [1.6653345369377348e-16, 1.6653345369377348e-16, 0.0]
accelerations: [0.0, 0.0, 0.0]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 839784080
Count :  32
POINT: 
 positions: [0.08777465367256829, 0.08777465367256829, 0.09949642846529107]
velocities: [0.44093822540279076, 0.44093822540279076, -0.557723065386227]
accelerations: [0.0, 0.0, -21.37]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 865882492
Count :  33
POINT: 
 positions: [0.09928244116520318, 0.09928244116520318, 0.0776628989147195]
velocities: [0.44093822540279076, 0.44093822540279076, -1.115446130772454]
accelerations: [0.0, 0.0, 21.37]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 891980904
Count :  34
POINT: 
 positions: [0.11079022865783807, 0.11079022865783807, 0.05582936936414794]
velocities: [0.44093822540279076, 0.44093822540279076, -0.5577230653862271]
accelerations: [0.0, 0.0, 21.37]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 918079316
Count :  35
POINT: 
 positions: [0.11774896330486316, 0.11774896330486316, 0.04855152618062408]
velocities: [-1.1102230246251565e-16, -1.1102230246251565e-16, 0.0]
accelerations: [0.0, 0.0, 0.0]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 944177728
Count :  36
POINT: 
 positions: [0.12575987838859004, 0.12575987838859004, 0.041152842335686]
velocities: [0.5851380270316452, 0.5851380270316452, -0.42337658803633726]
accelerations: [21.37, 21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 971559011
Count :  37
POINT: 
 positions: [0.14979262363977064, 0.14979262363977064, 0.029560247978410753]
velocities: [1.1702760540632904, 1.1702760540632904, -0.42337658803633726]
accelerations: [-21.37, -21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 998940295
Count :  38
POINT: 
 positions: [0.17382536889095124, 0.17382536889095124, 0.017967653621135504]
velocities: [0.5851380270316451, 0.5851380270316451, -0.42337658803633726]
accelerations: [-21.37, -21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 2
  nsecs:  26321578
Count :  39
POINT: 
 positions: [0.1818362839746781, 0.1818362839746781, 0.010568969776197427]
velocities: [0.0, 0.0, 0.0]
accelerations: [0.0, 0.0, 0.0]
effort: [1.0]
time_from_start: 
  secs: 2
  nsecs:  53702862
Count :  40
POINT: 
 positions: [0.18935593777909998, 0.18935593777909998, 0.008762729803597356]
velocities: [0.5669126948666714, 0.5669126948666714, -0.07275552637463709]
accelerations: [21.37, 21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 2
  nsecs:  80231298
Count :  41
POINT: 
 positions: [0.21191489919236567, 0.21191489919236567, 0.0068326394187827235]
velocities: [1.1338253897333428, 1.1338253897333428, -0.07275552637463709]
accelerations: [21.37, 21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 2
  nsecs: 106759735
Count :  42
POINT: 
 positions: [0.24575334131226417, 0.24575334131226417, 0.004902549033968092]
velocities: [1.133825389733343, 1.133825389733343, -0.07275552637463709]
accelerations: [-21.37, -21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 2
  nsecs: 133288172
Count :  43
POINT: 
 positions: [0.26831230272552986, 0.26831230272552986, 0.002972458649153459]
velocities: [0.5669126948666715, 0.5669126948666715, -0.07275552637463709]
accelerations: [-21.37, -21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 2
  nsecs: 159816609
Count :  44
POINT: 
 positions: [0.27583195652995174, 0.27583195652995174, 0.0011662186765533911]
velocities: [0.0, 0.0, 0.0]
accelerations: [0.0, 0.0, 0.0]
effort: [1.0]
time_from_start: 
  secs: 2
  nsecs: 186345046
Count :  45
POINT: 
 positions: [0.27583195652995174, 0.27583195652995174, 0.0011662186765533911]
velocities: [0.0, 0.0, 0.0]
accelerations: [0.0, 0.0, 0.0]
effort: [0.0]
time_from_start: 
  secs: 2
  nsecs: 286345046
Count :  46

CC = 0.015

total points :  65
POINT: 
 positions: [0.2719953984664712, 0.2719953984664712, 0.0024210042534921093]
velocities: [-0.4049376391904796, -0.4049376391904796, 0.07275552637463709]
accelerations: [-21.37, -21.37, 0.0]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs:  18948883
Count :  0
POINT: 
 positions: [0.2604857242760295, 0.2604857242760295, 0.0037996402426454185]
velocities: [-0.8098752783809592, -0.8098752783809592, 0.07275552637463709]
accelerations: [-21.37, -21.37, 0.0]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs:  37897767
Count :  1
POINT: 
 positions: [0.24130293395862673, 0.24130293395862673, 0.005178276231798727]
velocities: [-1.2148129175714388, -1.2148129175714388, 0.07275552637463709]
accelerations: [-21.37, -21.37, 0.0]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs:  56846650
Count :  2
POINT: 
 positions: [0.2163653065460031, 0.2163653065460031, 0.006556912220952036]
velocities: [-1.2148129175714386, -1.2148129175714386, 0.07275552637463709]
accelerations: [21.37, 21.37, 0.0]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs:  75795534
Count :  3
POINT: 
 positions: [0.1971825162286003, 0.1971825162286003, 0.007935548210105345]
velocities: [-0.809875278380959, -0.809875278380959, 0.07275552637463709]
accelerations: [21.37, 21.37, 0.0]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs:  94744417
Count :  4
POINT: 
 positions: [0.18567284203815865, 0.18567284203815865, 0.009314184199258654]
velocities: [-0.40493763919047954, -0.40493763919047954, 0.07275552637463709]
accelerations: [21.37, 21.37, 0.0]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 113693301
Count :  5
POINT: 
 positions: [0.1818362839746781, 0.1818362839746781, 0.010568969776197397]
velocities: [0.0, 0.0, 0.0]
accelerations: [0.0, 0.0, 0.0]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 132642184
Count :  6
POINT: 
 positions: [0.1782758772707995, 0.1782758772707995, 0.01412937648007603]
velocities: [-0.3900920180210968, -0.3900920180210968, 0.3900920180210968]
accelerations: [-21.37, -21.37, 21.37]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 150896373
Count :  7
POINT: 
 positions: [0.16759465715916366, 0.16759465715916366, 0.021831851740227254]
velocities: [-0.7801840360421936, -0.7801840360421936, 0.42337658803633726]
accelerations: [-21.37, -21.37, 0.0]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 169150562
Count :  8
POINT: 
 positions: [0.14979262363977064, 0.14979262363977064, 0.02956024797841075]
velocities: [-1.1702760540632904, -1.1702760540632904, 0.42337658803633726]
accelerations: [21.37, 21.37, 0.0]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 187404751
Count :  9
POINT: 
 positions: [0.13199059012037762, 0.13199059012037762, 0.037288644216594245]
velocities: [-0.7801840360421937, -0.7801840360421937, 0.42337658803633726]
accelerations: [21.37, 21.37, 0.0]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 205658940
Count :  10
POINT: 
 positions: [0.12130937000874177, 0.12130937000874177, 0.04499111947674547]
velocities: [-0.39009201802109683, -0.39009201802109683, 0.3900920180210968]
accelerations: [21.37, 21.37, -21.37]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 223913129
Count :  11
POINT: 
 positions: [0.11774896330486317, 0.11774896330486317, 0.04855152618062408]
velocities: [0.0, 0.0, 0.0]
accelerations: [0.0, 0.0, 0.0]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 242167318
Count :  12
POINT: 
 positions: [0.11309178615636505, 0.11309178615636505, 0.05320934581807935]
velocities: [-0.44093822540279076, -0.44093822540279076, 0.44617845230898157]
accelerations: [0.0, 0.0, 21.37]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 263046047
Count :  13
POINT: 
 positions: [0.10388555616225714, 0.10388555616225714, 0.06718280473044515]
velocities: [-0.44093822540279076, -0.44093822540279076, 0.8923569046179631]
accelerations: [0.0, 0.0, 21.37]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 283924777
Count :  14
POINT: 
 positions: [0.09467932616814924, 0.09467932616814924, 0.08814299309899384]
velocities: [-0.44093822540279076, -0.44093822540279076, 0.8923569046179632]
accelerations: [0.0, 0.0, -21.37]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 304803507
Count :  15
POINT: 
 positions: [0.08547309617404132, 0.08547309617404132, 0.10211645201135966]
velocities: [-0.44093822540279076, -0.44093822540279076, 0.4461784523089817]
accelerations: [0.0, 0.0, -21.37]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 325682236
Count :  16
POINT: 
 positions: [0.0808159190255432, 0.0808159190255432, 0.10677427164881492]
velocities: [1.1102230246251565e-16, 1.1102230246251565e-16, 0.0]
accelerations: [0.0, 0.0, 0.0]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 346560966
Count :  17
POINT: 
 positions: [0.07952246103975638, 0.07952246103975638, 0.11093187857814482]
velocities: [-0.07166344670845368, -0.07166344670845368, 0.42154017621047674]
accelerations: [0.0, 0.0, 21.37]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 366286758
Count :  18
POINT: 
 positions: [0.0781088427920572, 0.0781088427920572, 0.1234046993661345]
velocities: [-0.07166344670845368, -0.07166344670845368, 0.8430803524209535]
accelerations: [0.0, 0.0, 21.37]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 386012550
Count :  19
POINT: 
 positions: [0.07669522454435801, 0.07669522454435801, 0.14419273401278399]
velocities: [-0.07166344670845368, -0.07166344670845368, 1.2646205286314303]
accelerations: [0.0, 0.0, -21.37]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 405738342
Count :  20
POINT: 
 positions: [0.07528160629665882, 0.07528160629665882, 0.16498076865943348]
velocities: [-0.07166344670845368, -0.07166344670845368, 0.8430803524209536]
accelerations: [0.0, 0.0, -21.37]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 425464134
Count :  21
POINT: 
 positions: [0.07386798804895964, 0.07386798804895964, 0.17745358944742318]
velocities: [-0.07166344670845368, -0.07166344670845368, 0.4215401762104768]
accelerations: [0.0, 0.0, -21.37]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 445189926
Count :  22
POINT: 
 positions: [0.07257453006317283, 0.07257453006317283, 0.18161119637675305]
velocities: [-1.3877787807814457e-16, -1.3877787807814457e-16, 0.0]
accelerations: [0.0, 0.0, 0.0]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 464915718
Count :  23
POINT: 
 positions: [0.07257453006317283, 0.07257453006317283, 0.18161119637675305]
velocities: [0.0, 0.0, 0.0]
accelerations: [0.0, 0.0, 0.0]
effort: [0.0]
time_from_start: 
  secs: 1
  nsecs: 365237339
Count :  24
POINT: 
 positions: [0.07615260590921756, 0.07615260590921756, 0.18518927222279777]
velocities: [0.391058770084442, 0.391058770084442, 0.391058770084442]
accelerations: [21.37, 21.37, 21.37]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 383536767
Count :  25
POINT: 
 positions: [0.08688683344735207, 0.08688683344735207, 0.19572350305996597]
velocities: [0.782117540168884, 0.782117540168884, 0.6896629080550688]
accelerations: [21.37, 21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 401836195
Count :  26
POINT: 
 positions: [0.10477721267757628, 0.10477721267757628, 0.20834393958766248]
velocities: [1.173176310253326, 1.173176310253326, 0.6896629080550688]
accelerations: [21.37, 21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 420135623
Count :  27
POINT: 
 positions: [0.12803470567686775, 0.12803470567686775, 0.22096437611535902]
velocities: [1.1731763102533264, 1.1731763102533264, 0.6896629080550688]
accelerations: [-21.37, -21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 438435050
Count :  28
POINT: 
 positions: [0.14592508490709194, 0.14592508490709194, 0.23358481264305556]
velocities: [0.7821175401688842, 0.7821175401688842, 0.6896629080550688]
accelerations: [-21.37, -21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 456734478
Count :  29
POINT: 
 positions: [0.15665931244522646, 0.15665931244522646, 0.24411904348022376]
velocities: [0.39105877008444245, 0.39105877008444245, 0.39105877008444223]
accelerations: [-21.37, -21.37, -21.37]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 475033906
Count :  30
POINT: 
 positions: [0.16023738829127132, 0.16023738829127132, 0.2476971193262686]
velocities: [0.0, 0.0, -1.1102230246251565e-16]
accelerations: [0.0, 0.0, 0.0]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 493333333
Count :  31
POINT: 
 positions: [0.16023738829127132, 0.16023738829127132, 0.2476971193262686]
velocities: [0.0, 0.0, 0.0]
accelerations: [0.0, 0.0, 0.0]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 593333333
Count :  32
POINT: 
 positions: [0.1566593124452265, 0.1566593124452265, 0.24411904348022376]
velocities: [-0.391058770084442, -0.391058770084442, -0.391058770084442]
accelerations: [-21.37, -21.37, -21.37]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 611632761
Count :  33
POINT: 
 positions: [0.14592508490709197, 0.14592508490709197, 0.23358481264305556]
velocities: [-0.782117540168884, -0.782117540168884, -0.6896629080550688]
accelerations: [-21.37, -21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 629932189
Count :  34
POINT: 
 positions: [0.12803470567686775, 0.12803470567686775, 0.22096437611535905]
velocities: [-1.173176310253326, -1.173176310253326, -0.6896629080550688]
accelerations: [-21.37, -21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 648231616
Count :  35
POINT: 
 positions: [0.1047772126775763, 0.1047772126775763, 0.2083439395876625]
velocities: [-1.1731763102533264, -1.1731763102533264, -0.6896629080550688]
accelerations: [21.37, 21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 666531044
Count :  36
POINT: 
 positions: [0.08688683344735208, 0.08688683344735208, 0.19572350305996597]
velocities: [-0.7821175401688842, -0.7821175401688842, -0.6896629080550688]
accelerations: [21.37, 21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 684830472
Count :  37
POINT: 
 positions: [0.07615260590921756, 0.07615260590921756, 0.18518927222279777]
velocities: [-0.39105877008444245, -0.39105877008444245, -0.39105877008444223]
accelerations: [21.37, 21.37, 21.37]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 703129900
Count :  38
POINT: 
 positions: [0.07257453006317272, 0.07257453006317272, 0.18161119637675294]
velocities: [0.0, 0.0, 1.1102230246251565e-16]
accelerations: [0.0, 0.0, 0.0]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 721429327
Count :  39
POINT: 
 positions: [0.07386798804895954, 0.07386798804895954, 0.17745358944742304]
velocities: [0.07166344670845488, 0.07166344670845488, -0.42154017621047646]
accelerations: [0.0, 0.0, -21.37]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 741155119
Count :  40
POINT: 
 positions: [0.07528160629665875, 0.07528160629665875, 0.16498076865943337]
velocities: [0.07166344670845488, 0.07166344670845488, -0.8430803524209529]
accelerations: [0.0, 0.0, -21.37]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 760880911
Count :  41
POINT: 
 positions: [0.07669522454435795, 0.07669522454435795, 0.14419273401278393]
velocities: [0.07166344670845488, 0.07166344670845488, -1.2646205286314294]
accelerations: [0.0, 0.0, 21.37]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 780606703
Count :  42
POINT: 
 positions: [0.07810884279205717, 0.07810884279205717, 0.12340469936613448]
velocities: [0.07166344670845488, 0.07166344670845488, -0.8430803524209529]
accelerations: [0.0, 0.0, 21.37]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 800332495
Count :  43
POINT: 
 positions: [0.07952246103975638, 0.07952246103975638, 0.11093187857814481]
velocities: [0.07166344670845488, 0.07166344670845488, -0.42154017621047646]
accelerations: [0.0, 0.0, 21.37]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 820058288
Count :  44
POINT: 
 positions: [0.0808159190255432, 0.0808159190255432, 0.10677427164881492]
velocities: [1.6653345369377348e-16, 1.6653345369377348e-16, 0.0]
accelerations: [0.0, 0.0, 0.0]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 839784080
Count :  45
POINT: 
 positions: [0.08547309617404132, 0.08547309617404132, 0.10211645201135966]
velocities: [0.44093822540279076, 0.44093822540279076, -0.44617845230898157]
accelerations: [0.0, 0.0, -21.37]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 860662809
Count :  46
POINT: 
 positions: [0.09467932616814922, 0.09467932616814922, 0.08814299309899386]
velocities: [0.44093822540279076, 0.44093822540279076, -0.8923569046179631]
accelerations: [0.0, 0.0, -21.37]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 881541539
Count :  47
POINT: 
 positions: [0.10388555616225713, 0.10388555616225713, 0.06718280473044516]
velocities: [0.44093822540279076, 0.44093822540279076, -0.8923569046179632]
accelerations: [0.0, 0.0, 21.37]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 902420269
Count :  48
POINT: 
 positions: [0.11309178615636505, 0.11309178615636505, 0.053209345818079345]
velocities: [0.44093822540279076, 0.44093822540279076, -0.4461784523089817]
accelerations: [0.0, 0.0, 21.37]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 923298998
Count :  49
POINT: 
 positions: [0.11774896330486316, 0.11774896330486316, 0.04855152618062408]
velocities: [-1.1102230246251565e-16, -1.1102230246251565e-16, 0.0]
accelerations: [0.0, 0.0, 0.0]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 944177728
Count :  50
POINT: 
 positions: [0.12130937000874178, 0.12130937000874178, 0.04499111947674547]
velocities: [0.3900920180210968, 0.3900920180210968, -0.3900920180210968]
accelerations: [21.37, 21.37, -21.37]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 962431917
Count :  51
POINT: 
 positions: [0.13199059012037762, 0.13199059012037762, 0.03728864421659425]
velocities: [0.7801840360421936, 0.7801840360421936, -0.42337658803633726]
accelerations: [21.37, 21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 980686106
Count :  52
POINT: 
 positions: [0.14979262363977064, 0.14979262363977064, 0.029560247978410753]
velocities: [1.1702760540632904, 1.1702760540632904, -0.42337658803633726]
accelerations: [-21.37, -21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 1
  nsecs: 998940295
Count :  53
POINT: 
 positions: [0.16759465715916366, 0.16759465715916366, 0.021831851740227257]
velocities: [0.7801840360421937, 0.7801840360421937, -0.42337658803633726]
accelerations: [-21.37, -21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 2
  nsecs:  17194484
Count :  54
POINT: 
 positions: [0.1782758772707995, 0.1782758772707995, 0.014129376480076034]
velocities: [0.39009201802109683, 0.39009201802109683, -0.3900920180210968]
accelerations: [-21.37, -21.37, 21.37]
effort: [1.0]
time_from_start: 
  secs: 2
  nsecs:  35448673
Count :  55
POINT: 
 positions: [0.1818362839746781, 0.1818362839746781, 0.010568969776197427]
velocities: [0.0, 0.0, 0.0]
accelerations: [0.0, 0.0, 0.0]
effort: [1.0]
time_from_start: 
  secs: 2
  nsecs:  53702862
Count :  56
POINT: 
 positions: [0.18567284203815865, 0.18567284203815865, 0.00931418419925868]
velocities: [0.4049376391904796, 0.4049376391904796, -0.07275552637463709]
accelerations: [21.37, 21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 2
  nsecs:  72651745
Count :  57
POINT: 
 positions: [0.19718251622860034, 0.19718251622860034, 0.007935548210105371]
velocities: [0.8098752783809592, 0.8098752783809592, -0.07275552637463709]
accelerations: [21.37, 21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 2
  nsecs:  91600628
Count :  58
POINT: 
 positions: [0.2163653065460031, 0.2163653065460031, 0.006556912220952062]
velocities: [1.2148129175714388, 1.2148129175714388, -0.07275552637463709]
accelerations: [21.37, 21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 2
  nsecs: 110549512
Count :  59
POINT: 
 positions: [0.24130293395862673, 0.24130293395862673, 0.005178276231798753]
velocities: [1.2148129175714386, 1.2148129175714386, -0.07275552637463709]
accelerations: [-21.37, -21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 2
  nsecs: 129498395
Count :  60
POINT: 
 positions: [0.2604857242760295, 0.2604857242760295, 0.0037996402426454436]
velocities: [0.809875278380959, 0.809875278380959, -0.07275552637463709]
accelerations: [-21.37, -21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 2
  nsecs: 148447279
Count :  61
POINT: 
 positions: [0.2719953984664712, 0.2719953984664712, 0.0024210042534921344]
velocities: [0.40493763919047954, 0.40493763919047954, -0.07275552637463709]
accelerations: [-21.37, -21.37, 0.0]
effort: [1.0]
time_from_start: 
  secs: 2
  nsecs: 167396162
Count :  62
POINT: 
 positions: [0.27583195652995174, 0.27583195652995174, 0.0011662186765533911]
velocities: [0.0, 0.0, 0.0]
accelerations: [0.0, 0.0, 0.0]
effort: [1.0]
time_from_start: 
  secs: 2
  nsecs: 186345046
Count :  63
POINT: 
 positions: [0.27583195652995174, 0.27583195652995174, 0.0011662186765533911]
velocities: [0.0, 0.0, 0.0]
accelerations: [0.0, 0.0, 0.0]
effort: [0.0]
time_from_start: 
  secs: 2
  nsecs: 286345046
Count :  64

as I reduce the control cycle to 0.01 and lower the motion seems laggy during the return motion, i.e it seems like it is jumping steps or getting overridden by the next point. My objective is to achieve as low a control cycle as possible for smoother motions, We were earlier using UART and thought that was the bottleneck, but we have shifted currently to UDP and are sending msgs at 1.12ms times, so the current bottleneck now seems to be the way FastAccelStepper generates the motion and whether it is able to update at such high frequencies.

Your input would be greatly appreciated as you would have a better understanding of its capabilities, I am not able to figure out what the issue could be.

Thank you for your help in advance!

gin66 commented 4 days ago

You could try to reduce the forward planning time to a bare minimum using setForwardPlanningTimeInMs(uint8_t ms). If the motor behaves strangely, then the queue has run out of commands. I would assume, that on esp32 5ms could still work. It must be for sure larger than 4ms stepper task cycle time.

On the other side, with this high degree of control of the motion is the ramp generator in use at all ?

gin66 commented 4 days ago

Another try is to reduce the stepper task cycle time below 4ms. This can be done only by changing the code in this function: https://github.com/gin66/FastAccelStepper/blob/e57f7b4fe676d5ea3ee44a0048b92d1770e5c7da/src/StepperISR_esp32.cpp#L107

If this is e.g. 1ms and forward planning time is e.g. 2ms, this should be quite performant. If the cpu can cope with this load is another question. I think you need to ensure, that wifi and stepper are running on different cores.

gin66 commented 4 days ago

If this is successful, then I can extend engine.init with cycle time as an optional parameter

programmeddeath1 commented 4 days ago

Hi Thank you for your quick response!

1) Do i have to set setForwardPlanningTimeInMs for each stepper ?. Any reference or example would be helpful.

2) Also I will incrementally test with 15 ms 10 ms and then go to 5ms. For now even reaching 8ms, would be a great improvement in performance for me. The end goal being trying to push the device and see how performant it gets, I will later test in a more controlled environment, for going below 5ms, where changes need to be made in the ISR Code.

3) Regarding your question, I too had a doubt since you have mentioned the in the readme regarding multi-axis control that the library's ramp generator would be less useful and its recommended to implement low-level access directly using the library, At what point would the ramp generator prove insufficient? would that depend on how low I am going with my cycle time?

gin66 commented 4 days ago

Yes. The forward planning time needs to be set for each stepper and will be kept. In case a new stepper is allocated afterwards, then the forward planning time will be adjusted for all allocated steppers again. This will overwrite any earlier setting. If the forward planning time is set after all steppers are allocated, then the new value will be used and not overwritten anymore. This mean, if the steppers are allocated and configured in a loop, then the forward planning time need to be set in a second loop following the stepper allocation loop.

Thanks for your support in testing this functionality to the limits. Until now, I have only found a simulator for avr uCs. Great would be an esp32 simulator, so I can set up automated testing to check some of these advanced API features. Until then, those advanced features are only by design and not tested by me.

As I understand your use of FastAccelStepper the ramp generator will always ensure the limits for maximum acceleration and maximum speed. By design this is independent from the cycle time - unless there is any hardcoded value or implicit assumption in the code, which I do not believe, but am not 100% sure about. So there is no point, where the ramp generator will be insufficient. Just that the expectation of how the steppers should perform and the actual executed steps may not match, because of the constraints the ramp generator imposes on the stepper movements.

My expectation of the ramp generator is, that independent of the rate or magnitude of the changes in position/speed/acceleration, the stepper must always run within the limits of max speed/acceleration and always on the shortest round to the targeted position or speed.

programmeddeath1 commented 3 days ago

I tried adding ForwardPlanningTime as below -

  engine.init();
  for (int num = 0; num < MOTOR_COUNT; num++) {
    // Input for Limit Pins
    pinMode(MOTOR_LIMIT_PINS[num], INPUT_PULLUP);
    stepper[num] = engine.stepperConnectToPin(MOTOR_PUL_PINS[num]);
    if (stepper[num]) {
      stepper[num]->setDirectionPin(MOTOR_DIR_PINS[num]);
      // You might also need to set enable pin if you have one
      setMotorSpeedInMMPerSec(num, SPEED_IN_MM_S);
      setMotorAcceleration(num, ACCEL_IN_MM_S);
    }
  }

  // Set future planning time limit for lower control cycles
  for (int num = 0; num < MOTOR_COUNT; num++) {
      stepper[num]->setForwardPlanningTimeInMs(10);
  }

I tried with values 5, 10, 15. I didn't see any difference in my motion. I will attach videos of my execution to help you understand what the issue could be: Control Cycle = 0.02 secs

https://github.com/user-attachments/assets/c4eb0143-4654-4871-93a6-91e463d952ac

Control Cycle = 0.01 secs

https://github.com/user-attachments/assets/e4a2d040-e190-478e-9d35-9cd4be0da6cd

Control Cycle = 0.01 secs with fixed delay of 3ms

https://github.com/user-attachments/assets/a89207d0-1fc0-4413-aa99-1c7b8d61ae9a

The control Cycle of 0.01secs run with fixed dalay of 3ms, shows that the motion plan generates points based on smaller control cycle and follows the actual C path, but the execution at the esp end is suspect. Note: Just download the videos and play for now, for some reason its not playing on github directly

gin66 commented 3 days ago

Thanks for sharing the video. Gives an idea, how you use the system.

Your sequence of the initialization is ok: First the motor, then the forward planning time

From the code in FastaccelStepper I only see, that in this line the condition should be put in brackets () https://github.com/gin66/FastAccelStepper/blob/e57f7b4fe676d5ea3ee44a0048b92d1770e5c7da/src/FastAccelStepper.cpp#L386

Besides this, I cannot find anything suspicious in the code. If I find time the next days, I will make a test case running on simavr to check, that this function works as expected.

From the video I am not convinced, that the issue is related to FastAccelStepper. It could be network performance via UDP. This connection may lag due to WiFi communication, esp32 UDP/wifi stack implementation or esp32 task management. I assume, there is no flash write somewhere in the code. Perhaps it is a good idea to add a timestamp to the UDP commands and check on esp32 side, if expected UDP commands have arrived too late.

programmeddeath1 commented 3 days ago

https://github.com/user-attachments/assets/8a64b1f6-24f5-412b-a932-7d2270bc7a50

https://github.com/user-attachments/assets/70b4aca0-068f-441b-9f00-47cba3e71899

I have tracked the message communication and acknowledgment times, for both the control cycles, and even control cycles as low as 0.005, the messages do not lag, The ack1 is sent as soon as the esp receives the message, and ack2 is sent after the fastaccelstepper setPoint/vel/accel commands for the 3 motors and vacuum triggers on the GPIO are executed -

PointID | SentTime | Ack1ReceivedTime | Ack2ReceivedTime | CommunicationTimeAck1 | CommunicationTimeAck2 | TotalRoundTripTime | ContinuousAvg | ControlCycle -- | -- | -- | -- | -- | -- | -- | -- | -- 52026 | 1730112208 | 1730112208 | 1730112208 | 0.8039474487 | 0.3497600555 | 1.153707504 | 1.153707504 | NA 52027 | 1730112208 | 1730112208 | 1730112208 | 1.307725906 | 0.3340244293 | 1.641750336 | 1.39772892 | 0.001219987869 52028 | 1730112208 | 1730112208 | 1730112208 | 1.040220261 | 0.4224777222 | 1.462697983 | 1.419385274 | 0.01322007179 52029 | 1730112208 | 1730112208 | 1730112208 | 0.9036064148 | 0.3559589386 | 1.259565353 | 1.379430294 | 0.01307010651 52030 | 1730112208 | 1730112208 | 1730112208 | 0.9098052979 | 0.3447532654 | 1.254558563 | 1.354455948 | 0.0128698349 52031 | 1730112208 | 1730112208 | 1730112208 | 0.9143352509 | 0.3650188446 | 1.279354095 | 1.341938972 | 0.01289010048 52032 | 1730112208 | 1730112208 | 1730112208 | 0.8633136749 | 0.5404949188 | 1.403808594 | 1.35077749 | 0.01285004616 52033 | 1730112208 | 1730112208 | 1730112208 | 0.9951591492 | 0.287771225 | 1.282930374 | 1.3422966 | 0.01307988167 52034 | 1730112208 | 1730112208 | 1730112208 | 0.8809566498 | 0.4177093506 | 1.298666 | 1.337448756 | 0.01286005974 52035 | 1730112208 | 1730112208 | 1730112208 | 0.8842945099 | 0.369310379 | 1.253604889 | 1.329064369 | 0.01289987564 52036 | 1730112208 | 1730112208 | 1730112208 | 0.8840560913 | 0.3926753998 | 1.276731491 | 1.324306835 | 0.0129802227 52037 | 1730112208 | 1730112208 | 1730112208 | 0.8788108826 | 0.3726482391 | 1.251459122 | 1.318236192 | 0.01304984093 52038 | 1730112208 | 1730112208 | 1730112208 | 0.899553299 | 0.4088878632 | 1.308441162 | 1.317482728 | 0.01306009293 52039 | 1730112208 | 1730112208 | 1730112208 | 0.9727478027 | 0.3790855408 | 1.351833344 | 1.319936344 | 0.01320004463 52040 | 1730112208 | 1730112208 | 1730112208 | 1.022815704 | 0.4081726074 | 1.430988312 | 1.327339808 | 0.01314997673 52041 | 1730112208 | 1730112208 | 1730112208 | 0.9405612946 | 0.3881454468 | 1.328706741 | 1.327425241 | 0.01323986053 52042 | 1730112208 | 1730112208 | 1730112208 | 0.8940696716 | 0.3848075867 | 1.278877258 | 1.324569478 | 0.01306009293 52043 | 1730112208 | 1730112208 | 1730112208 | 0.9582042694 | 0.3700256348 | 1.328229904 | 1.324772835 | 0.01304006577 52044 | 1730112208 | 1730112208 | 1730112208 | 0.8945465088 | 0.4165172577 | 1.311063766 | 1.324051305 | 0.01322984695 52045 | 1730112208 | 1730112208 | 1730112208 | 0.8928775787 | 0.3826618195 | 1.275539398 | 1.32162571 | 0.01413011551 52046 | 1730112208 | 1730112208 | 1730112208 | 0.8642673492 | 0.4026889801 | 1.266956329 | 1.319022406 | 0.01411986351 52047 | 1730112208 | 1730112208 | 1730112208 | 0.9715557098 | 0.3564357758 | 1.327991486 | 1.319430091 | 0.01411008835 52048 | 1730112208 | 1730112208 | 1730112208 | 0.8988380432 | 0.4024505615 | 1.301288605 | 1.318641331 | 0.01434993744 52049 | 1730112208 | 1730112208 | 1730112208 | 0.9014606476 | 0.3752708435 | 1.276731491 | 1.316895088 | 0.01419997215 52050 | 1730112208 | 1730112208 | 1730112208 | 0.9865760803 | 0.3573894501 | 1.34396553 | 1.317977905 | 0.01419019699 52051 | 1730112208 | 1730112208 | 1730112208 | 0.8962154388 | 0.5376338959 | 1.433849335 | 1.322434499 | 0.01428985596 52052 | 1730112208 | 1730112208 | 1730112208 | 0.9055137634 | 0.4007816315 | 1.306295395 | 1.321836754 | 0.0127799511 52053 | 1730112208 | 1730112208 | 1730112208 | 0.9052753448 | 0.4031658173 | 1.308441162 | 1.32135834 | 0.01274013519 52054 | 1730112208 | 1730112208 | 1730112208 | 0.9016990662 | 0.3890991211 | 1.290798187 | 1.320304542 | 0.01262998581 52055 | 1730112208 | 1730112208 | 1730112208 | 0.9348392487 | 0.3678798676 | 1.302719116 | 1.319718361 | 0.01259994507 52056 | 1730112208 | 1730112208 | 1730112208 | 0.8955001831 | 0.3795623779 | 1.275062561 | 1.318277851 | 0.01262998581 52057 | 1730112208 | 1730112208 | 1730112208 | 1.076221466 | 0.3941059113 | 1.470327377 | 1.323029399 | 0.01261997223 52058 | 1730112208 | 1730112208 | 1730112208 | 0.9846687317 | 0.3886222839 | 1.373291016 | 1.324552478 | 0.01290011406 52059 | 1730112208 | 1730112208 | 1730112208 | 0.9205341339 | 0.364780426 | 1.28531456 | 1.323398422 | 0.01275992393 52060 | 1730112208 | 1730112208 | 1730112208 | 0.9489059448 | 0.3645420074 | 1.313447952 | 1.323114123 | 0.01261997223 52061 | 1730112209 | 1730112209 | 1730112209 | 0.8223056793 | 0.4091262817 | 1.231431961 | 1.320567396 | 0.9477100372 52062 | 1730112209 | 1730112209 | 1730112209 | 1.10077858 | 0.2830028534 | 1.383781433 | 1.322275883 | 0.01250004768 52063 | 1730112209 | 1730112209 | 1730112209 | 0.9276866913 | 0.3845691681 | 1.312255859 | 1.322012199 | 0.01253008842 52064 | 1730112209 | 1730112209 | 1730112209 | 0.8928775787 | 0.3890991211 | 1.2819767 | 1.320985647 | 0.0123898983 52065 | 1730112209 | 1730112209 | 1730112209 | 0.9138584137 | 0.515460968 | 1.429319382 | 1.323693991 | 0.01232004166 52066 | 1730112209 | 1730112209 | 1730112209 | 1.027822495 | 0.3933906555 | 1.42121315 | 1.326072507 | 0.0124900341 52067 | 1730112209 | 1730112209 | 1730112209 | 0.9288787842 | 0.3833770752 | 1.312255859 | 1.325743539 | 0.01255989075 52068 | 1730112209 | 1730112209 | 1730112209 | 0.9291172028 | 0.3836154938 | 1.312732697 | 1.325440961 | 0.01242995262 52069 | 1730112209 | 1730112209 | 1730112209 | 0.8947849274 | 0.3886222839 | 1.283407211 | 1.324485649 | 0.0123500824 52070 | 1730112209 | 1730112209 | 1730112209 | 0.9787082672 | 0.316619873 | 1.29532814 | 1.323837704 | 0.01241993904 52071 | 1730112209 | 1730112209 | 1730112209 | 0.8864402771 | 0.3633499146 | 1.249790192 | 1.322227976 | 0.01242995262 52072 | 1730112209 | 1730112209 | 1730112209 | 0.962972641 | 0.3430843353 | 1.306056976 | 1.321883912 | 0.01241016388 52073 | 1730112209 | 1730112209 | 1730112209 | 0.9129047394 | 0.3616809845 | 1.274585724 | 1.320898533 | 0.01248002052 52074 | 1730112210 | 1730112210 | 1730112210 | 0.8664131165 | 0.5345344543 | 1.400947571 | 1.322532187 | 0.01248979568 52075 | 1730112210 | 1730112210 | 1730112210 | 0.9765625 | 0.364780426 | 1.341342926 | 1.322908401 | 0.01251006126 52076 | 1730112210 | 1730112210 | 1730112210 | 0.9069442749 | 0.3745555878 | 1.281499863 | 1.322096469 | 0.1016099453 52077 | 1730112210 | 1730112210 | 1730112210 | 0.940322876 | 0.3936290741 | 1.33395195 | 1.322324459 | 0.01234006882 52078 | 1730112210 | 1730112210 | 1730112210 | 0.9653568268 | 0.3855228424 | 1.350879669 | 1.322863237 | 0.0124001503 52079 | 1730112210 | 1730112210 | 1730112210 | 0.8554458618 | 0.5397796631 | 1.395225525 | 1.324203279 | 0.01320981979 52080 | 1730112210 | 1730112210 | 1730112210 | 0.9515285492 | 0.3771781921 | 1.328706741 | 1.32428516 | 0.01252007484 52081 | 1730112210 | 1730112210 | 1730112210 | 0.8997917175 | 0.3716945648 | 1.271486282 | 1.323342323 | 0.01240992546 52082 | 1730112210 | 1730112210 | 1730112210 | 0.8842945099 | 0.3745555878 | 1.258850098 | 1.322210881 | 0.01233005524 52083 | 1730112210 | 1730112210 | 1730112210 | 0.8938312531 | 0.3750324249 | 1.268863678 | 1.321291101 | 0.01232004166 52084 | 1730112210 | 1730112210 | 1730112210 | 1.176834106 | 0.05745887756 | 1.234292984 | 1.319816557 | 0.01239991188 52085 | 1730112210 | 1730112210 | 1730112210 | 0.8945465088 | 0.3879070282 | 1.282453537 | 1.31919384 | 0.01239013672 52086 | 1730112210 | 1730112210 | 1730112210 | 0.9570121765 | 0.4644393921 | 1.421451569 | 1.320870196 | 0.01240992546 52087 | 1730112210 | 1730112210 | 1730112210 | 0.913143158 | 0.3817081451 | 1.294851303 | 1.320450537 | 0.01252007484 52088 | 1730112210 | 1730112210 | 1730112210 | 0.9000301361 | 0.4093647003 | 1.309394836 | 1.320275049 | 0.01235985756 52089 | 1730112210 | 1730112210 | 1730112210 | 0.9336471558 | 0.5588531494 | 1.492500305 | 1.322966069 | 0.01242017746 52090 | 1730112210 | 1730112210 | 1730112210 | 0.9427070618 | 0.3480911255 | 1.290798187 | 1.322471178 | 0.01258993149 52091 | 1730112210 | 1730112210 | 1730112210 | 0.9944438934 | 0.3607273102 | 1.355171204 | 1.322966633 | 0.01263999939 52092 | 1730112210 | 1730112210 | 1730112210 | 0.8893013 | 0.3824234009 | 1.271724701 | 1.322201828 | 0.01274991035 52093 | 1730112210 | 1730112210 | 1730112210 | 0.9138584137 | 0.3552436829 | 1.269102097 | 1.32142095 | 0.01260995865 52094 | 1730112210 | 1730112210 | 1730112210 | 0.9970664978 | 0.3743171692 | 1.371383667 | 1.322145047 | 0.01260018349 52095 | 1730112210 | 1730112210 | 1730112210 | 0.8885860443 | 0.545501709 | 1.434087753 | 1.323744229 | 0.01271986961 52096 | 1730112210 | 1730112210 | 1730112210 | 0.8933544159 | 0.3936290741 | 1.28698349 | 1.323226472 | 0.01278996468 52097 | 1730112210 | 1730112210 | 1730112210 | 0.926733017 | 0.4069805145 | 1.333713531 | 1.323372126 | 0.01266002655 52098 | 1730112210 | 1730112210 | 1730112210 | 0.9059906006 | 0.3499984741 | 1.255989075 | 1.32244907 | 0.01270008087 52099 | 1730112210 | 1730112210 | 1730112210 | 0.9760856628 | 0.3845691681 | 1.360654831 | 1.322965364 | 0.01267004013 52100 | 1730112210 | 1730112210 | 1730112210 | 0.9188652039 | 0.3626346588 | 1.281499863 | 1.322412491 | 0.01417994499 52101 | 1730112210 | 1730112210 | 1730112210 | 0.9605884552 | 0.3437995911 | 1.304388046 | 1.322175327 | 0.01416993141 52102 | 1730112210 | 1730112210 | 1730112210 | 0.9026527405 | 0.3800392151 | 1.282691956 | 1.321662556 | 0.01408004761 52103 | 1730112210 | 1730112210 | 1730112210 | 0.8962154388 | 0.3912448883 | 1.287460327 | 1.321224066 | 0.01414990425 52104 | 1730112210 | 1730112210 | 1730112210 | 0.8974075317 | 0.3798007965 | 1.277208328 | 1.320666905 | 0.01409006119 52105 | 1730112210 | 1730112210 | 1730112210 | 0.8945465088 | 0.3719329834 | 1.266479492 | 1.319989562 | 0.01411008835 52106 | 1730112210 | 1730112210 | 1730112210 | 0.9074211121 | 0.4017353058 | 1.309156418 | 1.31985582 | 0.01408004761 52107 | 1730112210 | 1730112210 | 1730112210 | 0.9112358093 | 0.3886222839 | 1.299858093 | 1.319611945 | 0.01305985451 52108 | 1730112210 | 1730112210 | 1730112210 | 0.8821487427 | 0.5688667297 | 1.451015472 | 1.32119512 | 0.01323008537 52109 | 1730112210 | 1730112210 | 1730112210 | 0.8776187897 | 0.3724098206 | 1.25002861 | 1.320347899 | 0.01320004463 52110 | 1730112210 | 1730112210 | 1730112210 | 0.8988380432 | 0.3702640533 | 1.269102097 | 1.319745008 | 0.01302981377 52111 | 1730112210 | 1730112210 | 1730112210 | 0.8940696716 | 0.373840332 | 1.267910004 | 1.319142275 | 0.01306009293 52112 | 1730112210 | 1730112210 | 1730112210 | 1.07049942 | 0.4243850708 | 1.494884491 | 1.321162301 | 0.01304006577 52113 | 1730112210 | 1730112210 | 1730112210 | 1.016139984 | 0.331401825 | 1.347541809 | 1.321462068 | 0.01338005066 52114 | 1730112210 | 1730112210 | 1730112210 | 0.9627342224 | 0.349521637 | 1.312255859 | 1.321358627 | 0.01327991486 52115 | 1730112210 | 1730112210 | 1730112210 | 0.8983612061 | 0.5362033844 | 1.43456459 | 1.322616471 | 0.0129199028 52116 | 1730112210 | 1730112210 | 1730112210 | 0.901222229 | 0.3831386566 | 1.284360886 | 1.32219608 | 0.0130200386 52117 | 1730112210 | 1730112210 | 1730112210 | 0.9543895721 | 0.3991127014 | 1.353502274 | 1.322536365 | 0.01290011406 52118 | 1730112210 | 1730112210 | 1730112210 | 0.8909702301 | 0.3814697266 | 1.272439957 | 1.321997694 | 0.01297998428 52119 | 1730112210 | 1730112210 | 1730112210 | 0.8749961853 | 0.3588199615 | 1.233816147 | 1.321059592 | 0.01292991638 52120 | 1730112210 | 1730112210 | 1730112210 | 0.9787082672 | 0.3287792206 | 1.307487488 | 1.320916728 | 0.01295995712 52121 | 1730112210 | 1730112210 | 1730112210 | 0.8978843689 | 0.3814697266 | 1.279354095 | 1.320483784 | 0.01294016838 52122 | 1730112210 | 1730112210 | 1730112210 | 0.9138584137 | 0.3709793091 | 1.284837723 | 1.320116299 | 0.0129199028 52123 | 1730112210 | 1730112210 | 1730112210 | 0.9164810181 | 0.3662109375 | 1.282691956 | 1.319734418 | 0.0128800869 52124 | 1730112210 | 1730112210 | 1730112210 | 1.005411148 | 0.433921814 | 1.439332962 | 1.320942484 | 0.01297998428 The lag by UDP is highly unlikely as I have tested and tracked the time in db in almost all scenarios with high and low control cycles. The max UDP lag is of random 1 or 2 msgs @3 ms which again should not be causing this behaviour as the lagged msg is random and not necessarily in one of the points near the return motion. I tried engine.init(CPU_CORE); to move the stepper execution to other core, but there was no noticeable change in the execution times.
gin66 commented 3 days ago

Thanks for checking, that UDP is not the issue. So there are two possibilities:

As mentioned, that I can add a test case only within a few days to check the general function. Besides the mentioned brackets, which may be the root cause, I am confident, that the feature is working on FastAccelStepper side.

programmeddeath1 commented 3 days ago

1) Sure, Ill make the changes and test once with the brackets around the condition but Im not sure if this can change anything since the order precedance is the same even with the brackets.

2) Regarding skipping the ramp generator and generating the commands directly from the UDP commands, can you provide any references as to how to go about this? I checked your low-level access comments and got a gist of it, but some reference would be really helpful.

If we can identify that FastAccelStepper is not the issue, then we might have to investigate on the driver and motor end. Most AC Servo drivers come with response times in the range of 10us, so that was planned to be my last option to investigate if we are reaching physical limits of the motors in terms of response times. You can check on your end as and when you get time, ill make the changes and see if it yields me any results

gin66 commented 3 hours ago

On master branch I have added a test case to check, if setForwardPlanningTimeInMs() works as expected and I have added the mentioned brackets for clarity. From my side, I do not see the reason for the observed behavior. Sorry for this.

From the video it appears, the stepper gets the command to stop or decelerate during movement. This does not hint to servo driver response time or physical limits of the motor.

In your first post, it can be observed, that the acceleration is in consecutive calls jump around the three values -21.37/0/+21.37. Could it be, that those initiate those stops ?

As this pick and place robot performs a complex motion for the steppers, it is not so obvious, what is correct behavior. How to determine, if the generated positions being sent via UDP are correct ?