-
Notifications
You must be signed in to change notification settings - Fork 73
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
How high can the control frequency be on the esp32 using this library? #288
Comments
You could try to reduce the forward planning time to a bare minimum using On the other side, with this high degree of control of the motion is the ramp generator in use at all ? |
Another try is to reduce the stepper task cycle time below 4ms. This can be done only by changing the code in this function: FastAccelStepper/src/StepperISR_esp32.cpp Line 107 in e57f7b4
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. |
If this is successful, then I can extend engine.init with cycle time as an optional parameter |
Hi Thank you for your quick response!
|
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. |
I tried adding ForwardPlanningTime as below -
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: 1500RPM_motion_0.02cc.mp4Control Cycle = 0.01 secs 1500RPM_motion_0.02cc.mp4Control Cycle = 0.01 secs with fixed delay of 3ms 1500RPM_motion_0.01cc_3msdelay.mp4The 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. |
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 FastAccelStepper/src/FastAccelStepper.cpp Line 386 in e57f7b4
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. |
1500RPM_motion_0.01cc_sliderview.mp41500RPM_motion_0.02cc_sliderview.mp4I 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 - <style type="text/css"></style>
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. |
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. |
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. |
On master branch I have added a test case to check, if 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 ? |
Hi the video named 1500RPM_motion_0.02cc_sliderview.mp4 , in one of the above commends runs at control cycle of 0.02, where it runs proper motion. The way we are verifying whether the positions are proper is I have run the entire trajectory generated at 0.01 control cycle, but added manual delays of 30ms between each point and run the motion as seen in - 1500RPM_motion_0.01cc_3msdelay.mp4 -above. It shows the positions are proper. How do we check if the accelerations/velocities are proper is currently only by running the motion physically :P sort of catch 22. But those acceleration spikes are normal, its following a trapezoidal trajectory generation, and the plots seem proper comparing to motions above control cycle of 0.02 which we could test physically. We do not currently have a physical simulator setup that can replicate the mass and inertia to simulate the acceleration and velocities properly, so that leaves us with testing on the actual hardware. My current suspect is now the drivers, the datasheet does not have the exact stat so I am waiting on response from their team. A basic google search on the driver gave me the control frequency on these drivers as 50Hz but again not in any of their specification sheets. If it is 50Hz it could explain why we are being limited to 0.02 right now. So once I can confirm that I can even test out using ForwardPlanningInMs with drivers at higher control frequency say 100 or 200 Hz. I tested with the brackets, there seems to be no difference, so ill check on the drivers and get back. |
Thanks for explanation.What is still not clear to me, which of the stepper‘s parameters of position, speed and/or acceleration are controlled and how this is done? What could be of interest to monitor The point is that for a given set of parameters, the ramp generator may decide, that stop needs to be executed and the next calculated set gives another result. With too high acceleration values the motion will be stuttering. If you control position and another value, then best sequence is to set speed/acceleration, then a move command. Do not call update |
How I am executing the motion is as follows,
I set the velocity and acceleration, then run the moveTo for the next position. So any specific point in the path generated is basically the speed and acceleration needed right now to move to the next position in the required time. This ensures the end-effector reaches the object on the conveyor at the right time.
This could be true for a moment of time in microseconds i guess, but its running pick and place on a moving conveyor at control cycles more than 0.02. Of course, we have not tested on mm level precision, where this could actually be causing impacts coz of unwanted movements for that small a time. |
Thanks for sharing. In general I am always confused to see a float being fed into a function expecting an integer. Apparently it works, but I would expect the compiler to issue some warning. First, Just my two cents from looking at the code. If the speed/acceleration values are all positive, then this can be safely ignored. |
The sequence of setting speed, acceleration and then position is fine and there is no possibility by task switching in between to cause an issue with unsynchronized updates. Only the |
Hello, I have a similar issue. At the beginning of the thread, it seems like a ROS trajectory output, which I also use. My question is about creating the command queue. If I understand correctly, the stepper creates a queue of commands that arrive faster than it can process each one, so it continues with the original target value and then moves on to the next in the queue – is that correct? If so, how is the queue generated over time? I'm trying to understand if, when I set speed and acceleration and then call moveTo, the motor moves... and if, before it finishes moving, another speed, acceleration, and moveTo are called, will the new speed and acceleration be applied only at the new position, or will they change immediately when moveTo is called? |
The ramp generator fills the stepper queue with commands and keeps track of position/pulse rate at queue end … normally some time in the future. For very low speeds e.g. 1step/s this future can be even 2 seconds: one command in process and one command prepared in queue. For a move to complete, it may need 1 or 10 or 100000 commands to complete - depending on the move. Those commands can be steps, multiple steps or pauses. The queue will be minimally filled to have 20ms planned in the future. Any new move/moveTo/stop/applySpeedAcceleration will only append command to queue end and will not change existing commands. If one move is 1 step at 1step/s, then the next command will be processed after completing the 1s. |
The ramp generator is processed every 4ms in cyclic interrupt or task depending on the uC |
So the queue only stores the position? |
The struct is here: FastAccelStepper/src/fas_arch/common.h Line 50 in f83a711
|
The ramp generator keeps its own queue end related data, which is defined here:
|
The queue does not care about the current speed/acceleration, so the queue end structure only keeps position related info. The ramp generator need to know those values, so more data is kept. If commands are removed from the queue, then the ramp generator’s data structure would be out of sync. |
This means that for precise synchronized movement of multiple motors to achieve linear motion of my manipulator's end effector, the high-level application of FAS is not very suitable. It is not possible to accurately set acceleration and speed at transition states over time because, when I want to use Moveto at exact time intervals designated for movement, the previous motion is already decelerating at that moment? I tried to address this issue with a slight "lead," setting the commands earlier than the end of the movement, but this causes significant desynchronization. |
That’s right. Explanation is given in the readme: https://github.com/gin66/FastAccelStepper?tab=readme-ov-file#usage-for-multi-axis-applications |
Alright, I'll try to dive into it and see what can be done. Thanks a lot for the consultation. I really appreciate your work, as it allows me to do things I could hardly manage on my own. Do you have any suggestions on where to start studying the problem so that it makes sense for my project? And is there any description on how to work with the low-level aspects beyond the documented API? It's quite a complex topic for me... and I would need something detailed. |
some doc is in #86 examples: |
Hi @gin66, I'm very much interested in high-frequency positioning. My ESPs control loop runs at 1ms or lower and likewise, the moveTo() is called. The servo I use has a step/dir interface that accepts pulses up to 300kHz. Any chance we get a simple API like BR |
I have another question: How is it possible to achieve high frequencies using "addQueueEntry"? According to the description, it is possible to have MIN_CMD_TICKS set to 3200, which translates to 5000 steps per second. Or did I misunderstand something? |
The minimal command duration is defined by |
Thanks, that's clear. Now I "just" need to calculate it so that the accelerations and decelerations work for my application |
a single command has a fixed pulse rate. Acceleration and deceleration needs several commands in sequence. |
That's what I meant, for example, 6000 ticks/10 steps, then the next command 5000 ticks/10 steps, and so on... acceleration and conversely deceleration, or the same number of ticks but with a decreasing or increasing number of steps. Is that correct? |
The algorithm is bit complex. For slow speeds (lower than 1kHz) normally each command contains one step. If the step rate is even lower than 65535 ticks, then pause commands will be included between steps. For higher speeds, the algorithm tries to settle on a 2ms command time by requesting several steps per command. Depending on the position on the ramp, or if during coasting the deceleration start is approaching, the number of steps and thus the command time can be decreased. |
I understand that the implementation will be complex, but essentially it's about combining the pause between commands, tick and step, and tick/step (it’s important not to end up with a remainder or exceed the MCU frequency). I'll try to put it together somehow |
@gin66 I've implemented a very specialized and rudimentary version of this awesome library without acceleration and learnt a ton from your work. To compare the libraries, a benchmark has been setup, in which a sine wave target signal (10Hz) has to be followed. Examples of the pulse following are depicted below. The blue line is the target position, the green line is the current position from "FastAccelStepper" and the red curve is the current position from "FastNonAccelStepper". The FastAccelStepper settings from the benchmark script resulted in significant position lag. Furthermore, the "FastAccelStepper" trajectory looks a bit jittery. Do you have some settings in mind, which would improve the benchmark behavior? BR |
Thanks for this great visualization and interesting benchmark. Happy to hear, that my lib has helped you to write an own stepper control library. I have noted, that you are using the mcpwm/pcnt -combo. This will be troublesome to port to next espidf-version, that‘s why I recommend to use the rmt-module instead. Due to the numerous restrictions imposed by espressif on access to low level hardware, I do not plan to maintain mcpwm/pcnt for espidf v5.x. The visualization shows nicely the delay introduced by the ramp generator. The ramp generator is invoked every 4ms and plans the movement up to 20ms into the future. This is the reason for the right shift. The reason for the jittery is IMHO due to the uncorrelated relation between executed commands and the 4ms stepper task. The ramp generator tries to make the commands 2ms long. If the ramp generator is able to add one more or less will for sure make a difference in the trajectory and can be interpreted as jitter. Possible improvement is to use Another possibility is to reduce the acceleration to a value close to (2pi10Hz)^2*1000. If I am not mistaken, this should be the max needed acceleration to follow the sine wave. |
Thank you for the hint, I might take a look into RMT then. Here are some examples w/ the corresponding settings: Reducing the acceleration helped removing the jitter but also increased the lag. The forward planning time didn't have a significant impact, as it was set to 8ms in my previous test. Shall I reduce the stepper task period to 2ms? |
Thanks for the new measurements. Actually I am surprised, that forward planning time 1ms has worked without motor stalls. Reducing the task period together with short planning time should improve the results. |
Thanks again for measurements. For esp32 adding the option to adjust the stepper task rate makes apparently sense. Then the app developers have more control about FastAccelStepper performance. The 4ms task rate was just a carry over from avr. In order to have as much code overlap as possible and reuse the test suite from avr, the 4ms will remain to be the default. I do not remember to have hit a limit with esp32 load or bad performance, but the mcpwm/pcnt combo is sensitive to too long interrupt blockages by design. There is code included to recover from an overrun, but difficult to test. esp32 cpu load measurements haven’t been performed., but I know, that writing to flash while running a stepper is not a good idea. The stepper task will stop filling the queue, which leads to an abrupt stop and with delay a sudden restart at previous speed. At least no step will be lost, because the interrupt service routines are in IRAM. For espidf 5.x I am not so sure anymore, because here a good deal of espressif code is in use. |
…he stepper task rate to e.g. 1ms (see #288 for reference)
Although If negative accelerationis not accepted by the function call setAcceleration, do you mean to say that the motion is running purely based on the position and speed controls provided by the trajectory? My question is for control cycles more than 0.02, the motion is quite accurate, and we seem to be facing stops or speed change issues only at higher update rates (< 0.02), should I try running the motion with signed int values for speed to see if the issue still persists below 0.02 control cycle. For me the current culprit is the driver which we are in the process of upgrading. Based on the above plots by users above , it seems the forwardPlanning is working even for upto 1ms, so can we for sure claim this is not an issue with the processing on the end of the esp32 or library? |
„For sure“ is difficult to say. It highly depends on the other code running on the esp32 in which FastAccelStepper is a part of. The OS is normally configured with 1ms task rate. So 1ms delay in the StepperTask loop may result in the StepperTask only running every 2ms. |
Yeah but still my current requirements are not that high either. I am working with 20ms currently, so even if I can get the cycle down to 10ms or 5ms, we are still reaching industrial motion controller standards. Upto 10ms I guess should be feasible or do I need to run cpu utilization scripts parallel with the stepper calls to confirm if this works? I'm currently stuck between both where I am unable to confirm if the bottleneck is the driver or the esp32. |
@ChrGri has obtained good results at 2ms delay. Perhaps you can try something like 2ms delay and 5ms forward planning |
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.015
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!
The text was updated successfully, but these errors were encountered: