gin66 / FastAccelStepper

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

3 Parallel stepper movement for delta robot #207

Closed programmeddeath1 closed 3 months ago

programmeddeath1 commented 7 months ago

My application is trying to get the esp32 to run 3 stepper motors to move the arm of a parallel delta robot. The distance,speed and accel are received through usb serial communication. I need the esp32 to control 3 motors using the step dir pins.

I tried running three separate motors as an array and moving them using position parameters, but I noticed that each motor starts with a delay to the other motors since they are sequentially triggered.

Is it possible to run the fastaccelstepper motors using a background service? Something on the lines of creating a service and moving the stepper[num]->keepRunning(); as a background task.

How else can synchronized movement be done using FastAccelStepper?

I was earlier running my 3 steppers using the ESP-FlexyStepper library, but i was facing jitter issues and high motor vibrations with NEMA 23 motors with higher torque. The motor movements using FastAccelStepper are more stable, even at higher speeds, but, the non-synchronized movement is causing jerks.

Is this possible to do with this library if I move the motor movement to a background task, where the steps to move are received as a call to the background task, and it runs independently of the core 1 loop() activites?

gin66 commented 7 months ago

Yes, but I have not tested this configuration. The FastAcelStepper API calls can be called from a background task. This task shall not have the maximum possible priority, because the cyclic internal background task is running at that priority.

gin66 commented 7 months ago

in addition please read: https://github.com/gin66/FastAccelStepper#usage-for-multi-axis-applications

programmeddeath1 commented 7 months ago

I tried, normally just running the motors as is in the fastaccelstepper library ` void setMotorPosition(int num, float pos_mm) { if (stepper[num]) { int pos_steps = static_cast(pos_mm * STEPS_PER_MM); stepper[num]->moveTo(pos_steps); } }

void setMotorSpeedInMMPerSec(int num, float speed_mm_s) { if (stepper[num]) { float speed_steps_s = speed_mm_s * STEPS_PER_MM; stepper[num]->setSpeedInHz(speed_steps_s); } }

void setMotorAcceleration(int num, float accel_mm_s2) { if (stepper[num]) { float accel_steps_s2 = accel_mm_s2 * STEPS_PER_MM; stepper[num]->setAcceleration(accel_steps_s2); } }`

I call these functions for every point that is executed in a trajectory plan for pick and place. The motors seem to be running in sync and following the trajectory properly. But over time the motors seem to be giving an offset. Overtime I ran it for 1 hr at a fixed acceleration and for half hour at a higher fixed acceleration, the motor seems to be missing its repeatability of its position overtime.

For the same motion run in a loop for an hour, the motors that are moving more seem to be running extra steps or losing steps over time. This does not happen for a fixed motion moving at slower speeds, but for certain faster motions where the direction changes frequently, the motors seems to be losing steps and there seems to be an incremental offset in its position. 20231118_172120 The slider run by the motor starts at the extreme left marker, and after around 15minutes of same motion the final position is as shown currently, and if run longer the offset keeps growing higher.

Do you know what could be the issue here?

gin66 commented 7 months ago

Deviations can be caused by:

In order to get down to the root cause, the esp32 has a good device to count the generated pulses from the uC taking into consideration step and direction. Please attach a pulse counter to one of the steppers with deviation. This can be done with stepper-> attachToPulseCounter(7);. Now the position of the motor and the pulse counter should be synchronized. Unfortunately that pulse counter is limited to -16384…16384 with wrap around. So best to check at a known position (ideally in standstill) the value of the attached pulse counter. It should be always the same. The pulse counter can be read with readPulseCounter()ˋ

gin66 commented 7 months ago

btw: which library version do you use ? latest is 0.30.6

programmeddeath1 commented 7 months ago

I am installing from the arduino ide. The library version is 0.30.0. Would that be a problem? Can i zip the latest version and add it to the arduino library path? I will try getting to the root cause using a pulseCounter as you have mentioned. Ill try to see for my current motion if it is generating the same counter for that motion.

programmeddeath1 commented 7 months ago

I tried using the pulse counter, the pulse count at the final static position is the same after n cycles.

[INFO] [1701240530.657223]: Pulse Count 48: 
[INFO] [1701240536.661793]: Pulse Count 48: 
[INFO] [1701240542.592957]: Pulse Count 48: 
[INFO] [1701240548.560703]: Pulse Count 48: 
[INFO] [1701240554.500934]: Pulse Count 48: 
[INFO] [1701240560.399634]: Pulse Count 48: 
[INFO] [1701240566.350601]: Pulse Count 48: 
[INFO] [1701240572.313526]: Pulse Count 48: 
[INFO] [1701240578.257484]: Pulse Count 48: 
[INFO] [1701240584.214447]: Pulse Count 48: 
[INFO] [1701240590.182404]: Pulse Count 48: 

Which means the pulse is properly being generated by the ESP right? Could this be a direction change issue? The mechanical couplers are extremely tight, The slider as seen in the image above is overshooting the final position marked in blue using markers. Thus could this be a deceleration issue where it isnt able to stop in the needed position due to momentum? It is moving at a moderately high RPM towards the end. The 12 points generated for the 3 motors are as follows -

Buffer published as data: 0
POINT: 
 positions: [0.10524031426575722, 0.10524031426575725, 0.14906670474891437]
velocities: [0.0, 0.0, 0.0]
accelerations: [0.08585606383134377, 0.08585606383134362, -0.6089329615276501]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs:         0
Count :  0
buffer :  data: 0
total points :  12
Sleeping for 0.0 time before next point
POINT: 
 positions: [0.11967084015636975, 0.11967084015636975, 0.046718396722194244]
velocities: [0.04977847229444247, 0.04977847229444237, -0.3530531357007181]
accelerations: [-0.08585606383134377, -0.08585606383134362, 0.6089329615276501]
effort: [0.0]
time_from_start: 
  secs: 0
  nsecs: 579789826
Count :  1
buffer :  data: 0
total points :  12
Sleeping for 0.5797898260000001 time before next point
POINT: 
 positions: [0.11967084015636975, 0.11967084015636975, 0.046718396722194244]
velocities: [0.0, 0.0, 0.0]
accelerations: [0.0, 0.0, 0.0]
effort: [0.0]
time_from_start: 
  secs: 1
  nsecs: 159579652
Count :  2
buffer :  data: 0
total points :  12
Sleeping for 0.5797898260000001 time before next point
POINT: 
 positions: [0.17211403014298315, 0.17211403014298315, 0.10824403160871277]
velocities: [0.0, 0.0, 0.0]
accelerations: [3.6203292092413437, 3.6203292092413437, 4.247320827616291]
effort: [0.0]
time_from_start: 
  secs: 1
  nsecs: 169579652
Count :  3
buffer :  data: 0
total points :  12
Sleeping for 0.009999999999999787 time before next point
POINT: 
 positions: [0.22455722012959656, 0.22455722012959656, 0.1697696664952313]
velocities: [0.6162168652906697, 0.6162168652906697, 0.7229372178631082]
accelerations: [-3.6203292092413437, -3.6203292092413437, -4.247320827616291]
effort: [0.0]
time_from_start: 
  secs: 1
  nsecs: 329789826
Count :  4
buffer :  data: 0
total points :  12
Sleeping for 0.16021017400000015 time before next point
POINT: 
 positions: [0.22455722012959656, 0.22455722012959656, 0.1697696664952313]
velocities: [0.0, 0.0, 0.0]
accelerations: [0.0, 0.0, 0.0]
effort: [0.0]
time_from_start: 
  secs: 1
  nsecs: 500000000
Count :  5
buffer :  data: 0
total points :  12
Sleeping for 0.17021017399999994 time before next point
POINT: 
 positions: [0.17211403014298315, 0.17211403014298315, 0.10824403160871277]
velocities: [0.0, 0.0, 0.0]
accelerations: [-3.6248887021784806, -3.6248887021784806, -4.252669962514255]
effort: [0.0]
time_from_start: 
  secs: 1
  nsecs: 510000000
Count :  6
buffer :  data: 0
total points :  12
Sleeping for 0.010000000000000009 time before next point
POINT: 
 positions: [0.11967084015636975, 0.11967084015636975, 0.046718396722194244]
velocities: [-0.6166047792365456, -0.6166047792365456, -0.7233923132111876]
accelerations: [3.6248887021784806, 3.6248887021784806, 4.252669962514255]
effort: [0.0]
time_from_start: 
  secs: 1
  nsecs: 670103093
Count :  7
buffer :  data: 0
total points :  12
Sleeping for 0.16010309300000003 time before next point
POINT: 
 positions: [0.11967084015636975, 0.11967084015636975, 0.046718396722194244]
velocities: [0.0, 0.0, 0.0]
accelerations: [0.0, 0.0, 0.0]
effort: [0.0]
time_from_start: 
  secs: 1
  nsecs: 840206186
Count :  8
buffer :  data: 0
total points :  12
Sleeping for 0.17010309300000004 time before next point
POINT: 
 positions: [0.10528658305684085, 0.10528658305684085, 0.14917511813699919]
velocities: [0.0, 0.0, 0.0]
accelerations: [-0.08554917929052752, -0.08554917929052752, 0.6093528757993242]
effort: [0.0]
time_from_start: 
  secs: 1
  nsecs: 850206186
Count :  9
buffer :  data: 0
total points :  12
Sleeping for 0.010000000000000009 time before next point
POINT: 
 positions: [0.09090232595731196, 0.09090232595731196, 0.2516318395518041]
velocities: [-0.04960970448548632, -0.04960970448548632, 0.353361848079505]
accelerations: [0.08554917929052752, 0.08554917929052752, -0.6093528757993242]
effort: [0.0]
time_from_start: 
  secs: 2
  nsecs: 420103093
Count :  10
buffer :  data: 0
total points :  12
Sleeping for 0.5698969069999997 time before next point
POINT: 
 positions: [0.09090232595731196, 0.09090232595731196, 0.2516318395518041]
velocities: [0.0, 0.0, 0.0]
accelerations: [0.0, 0.0, 0.0]
effort: [0.0]
time_from_start: 
  secs: 3
  nsecs:         0
Count :  11
buffer :  data: 0
total points :  12
Sleeping for 0.5798969070000002 time before next point

The max speed is 0.616mm/s, which is around is around 500RPM for our setup stepper motor. This is not that high a speed for it to be overshooting or stopping ahead.

gin66 commented 7 months ago

Thanks for testing, so what remains after excluding library bug based on your test:

programmeddeath1 commented 7 months ago

I have a slider where a single revolution of the shaft results in 70mm movement of the slider. 1 revolution is 1600 steps. Iv noticed that the steps execution is not exactly accurate. The center of the slider should aligh with the markings. The 3 markings are 100mm, 200mm and 300mm. Im giving the same steps using the conversion 100(1600/70) & 200(1600/70) ... I have moved the motor shaft using the coupler manually exactly 1 revolution equals slider distance of 70mm. Mechanically it moves which means the stepper is possibly missing steps while executing the higher distance positions.

https://github.com/gin66/FastAccelStepper/assets/44861370/361c7c4f-3fab-40e9-a959-131c0fe9f7c1

1) Yes the load is asymmetric, as you see When the slider moves down it has lesser load compared to when the slider moves up. 2) Should i be adding some delay during the direction changes? what should that value be? 3) No im not using auto enable.

Should i be adding some delays to take into account any minor friction coefficien values for this system?

gin66 commented 7 months ago

Could you please try a stepper without load/mechanics? If the stepper maintains correct position, then the whole chain of sw/esp32/stepper controller/stepper works well. What remains is mechanics

beniroquai commented 7 months ago

Hey @gin66 this may be a related question - not sure. Is it possible to use the attachToPulseCounter to create a callback whenever e.g. 100 steps are performed? As far as I understood I cannot get a trigger for every pulse in the "main" thread on the ESP32, is this correct? Thanks!

gin66 commented 7 months ago

This would be a possible use case for an attached pulse counter and works with polling. You can even use it to generate an interrupt using pcnt_isr_handler_add(). Setting the pulse counter values still are the for this use.

And yes, in the main thread you will not get a trigger for every pulse, which at high speed would not work anyway.

Perhaps you can attach an interrupt to the step pin. Not sure, if this breaks the mcpwm/pcnt function of the pin,

beniroquai commented 7 months ago

I think this makes sense, I just don't know where to start ;-) Do you have any example usecase anywhere, which could serve as a first step? I guess using an interrupt on an output doesn't work, or?

gin66 commented 7 months ago

I haven’t tried, but I was able to connect the mcpwm output and the pcnt input to the same processor pin/pad. So perhaps the pin interrupt can be added, too !?

beniroquai commented 7 months ago

Interesting. Will try

Am Mi., 6. Dez. 2023 um 16:02 Uhr schrieb gin66 @.***>:

I haven’t tried, but I was able to connect the mcpwm output and the pcnt input to the same processor pin/pad. So perhaps the pin interrupt can be added, too !?

— Reply to this email directly, view it on GitHub https://github.com/gin66/FastAccelStepper/issues/207#issuecomment-1843066750, or unsubscribe https://github.com/notifications/unsubscribe-auth/ABBE5OA6P6KNAWYDGEO6LW3YICCINAVCNFSM6AAAAAA7MBTNKGVHI2DSMVQWIX3LMV43OSLTON2WKQ3PNVWWK3TUHMYTQNBTGA3DMNZVGA . You are receiving this because you commented.Message ID: @.***>

gin66 commented 6 months ago

Difficult to support you on this topic. Just from the one liner, the moveTo should be after speed/acceleration setting.

Which „lines of code“ do you assume to be skipped by esp32 ?

gin66 commented 6 months ago

and please check the return values from moveTo, setAcceleration and setSpeed. This may help to narrow down on possible problems.

programmeddeath1 commented 6 months ago

Just referencing what the previous comment was. - Hey I could'nt sit on this for a while. I have checked the deviation is mostly due to kickback load from the other two motors and the final positions are quite accurate. The path planning that we do is executed quite synchronously and runs well with the library. I am only facing sync issues when I run the homing function to reset the sliders to their default position. What I am getting is erratic behaviour at times as if the esp32 is skipping certain lines of code - This is proper homing motion that works generally

https://github.com/gin66/FastAccelStepper/assets/13079443/076cef1c-589f-46d3-ad0d-ea8f6a9156aa

But it works after a few tries, it keeps bugging out randomly with async execution or runs without stopping -

https://github.com/gin66/FastAccelStepper/assets/13079443/0309c1ec-7fa9-454b-81ce-0cd36d8bc8e3

https://github.com/gin66/FastAccelStepper/assets/13079443/34617102-d167-4b8d-b806-cc308633a74d It either overshoots as the 2nd video or runs less steps than sent by esp as in the 1st video. The code logic is same for all three, the motor runs to the top until limit switch is triggered. Then all three motors are moved to the same fixed position in steps. It seems sometimes the esp is sending a few commands but since all three are running in the same core it might be prioritizing one or the other or missing program lines for individual motors. But after proper homing if i send a motion plan, it executes for all three motors synchronously and works perfect. The code logic for moving the 3 motors a fixed distance is as follows


//Serial.println("Homing Done");
  for (int num = 0; num < MOTOR_COUNT; num++) {
    set_point(num, HOME_POS, SPEED_IN_MM_S, ACCEL_IN_MM_S);
  }
where set_point calls a function which has- > - stepper[num]->moveTo(pos_steps);stepper[num]->setSpeedInHz(speed_steps_s);stepper[num]->setAcceleration(accel_steps_s2);
```-

Okay ill try changing the moveTo after speed and accel. Ill display and check the return values when they bug out and check them.
programmeddeath1 commented 6 months ago

This is the current homing code run from setup


void setup()
{
    //Atach one motor to pulse counter
  stepper[0]-> attachToPulseCounter(7);

  // Home and be ready for input

  delay(3500);
  // Serial.println("Homing");
  motorHoming();

  delay(1000);
  // Serial.println("Homing Done");

  for (int num = 0; num < MOTOR_COUNT; num++) {
    set_point(num, HOME_POS, SPEED_IN_MM_S, ACCEL_IN_MM_S);
  }

  delay(2000);
  nh.loginfo("Ready for Trjectory now!!");

}

After the homing, the set_point behaves erratically. I printed the currentPosition of each motors before and after execution, it shows constant values, which means the library is sending proper values to the drives right?

gin66 commented 6 months ago

startHoming()is not there. Anyway, the checkHoming() will not work as expected. The scheme in that function could be - among others - like this:

  1. check if the switch is LOW, then call stopMove(). This is a non-blocking call, which stops the motor with deceleration, which will take a while.
  2. then wait until all three switches are LOW
  3. if this has achieved, wait for all motor reports on isRunning() being stopped
  4. Now call setCurrentPosition(0) for each motor

Or forceStopAndNewPosition(0) is used instead

Or int32_t home = getCurrentPosition() is used at first time to reach the limit switch to record the home position for each motor once (!), then call stopMove() and when all motors are stopped, zero the home position by setCurrentPosition(getCurrentPosition()-home) with each motor‘s own home position. eventually add a moveTo(0)

gin66 commented 6 months ago

Just have revisited your code. Your stopMove(), serCurrentPosition() should be ok, if you call it only once per motor.

gin66 commented 6 months ago

and perhaps check the lines to your switches, so that you do not have electrical noise on the wires preventing reliable detection of high or low by the esp32

programmeddeath1 commented 5 months ago

Hey thank you so much for your quick response! It seems it is an issue with the currentPosition(0) not getting properly update after the stopMove() execution. I updated the checkHoming function as below -

    for (int num = 0; num < MOTOR_COUNT; num++) {
        if (digitalRead(MOTOR_LIMIT_PINS[num]) == LOW) { // Assuming LOW when triggered
            // stepper[num]->forceStopAndNewPosition(0);
            stepper[num]->stopMove();
            // stepper[num]->setCurrentPosition(0); // Set current position as home
        } 
        // else {
        //     return false; // Homing is still in progress
        // }
    }
    if (digitalRead(MOTOR_LIMIT_PINS[0]) == HIGH || digitalRead(MOTOR_LIMIT_PINS[1]) == HIGH || digitalRead(MOTOR_LIMIT_PINS[2]) == HIGH){
      // Homing is still in progress
      return false;
    }
    delay(100);
    while(!areMotorsAtTarget()){
      delay(10);

    }
    stepper[0]->setCurrentPosition(0); // Set current position as home
    stepper[1]->setCurrentPosition(0); // Set current position as home
    stepper[2]->setCurrentPosition(0); // Set current position as home

    return true; // All motors are homed

This works properly for the most part. Except during some cases the motors reach the home position and touch the limit switch, but the motor seems to spin internally for sometime before the next moveTo is triggered. Does the areMotorsAtTarget() take some time after the motors have actually stopped or is it instantaneous after the motor execution command is completed from the esp?

programmeddeath1 commented 5 months ago

Hii I have been able to fix the above issues, had to add a delay during the motor LOW check, because it was maybe overwhelming the cpu and was not registering the last limit switch value in time.

I am sometimes facing synchronization issues with the motors, they seem to be running out of sync during homing. The distance travelled by all the three motors is not exactly the same.

I ran a test for the set_point(num, HOME_POS, SPEED_IN_MM_S, ACCEL_IN_MM_S); after homing, each of the motors seem to be travelling different distances at random times.

Could EMF or the esp load change the way in which these motors are being triggered? I am having two issues 1) I ran the homing functions with different accelerations, same velocity and same position. I am running the motors to 88mm distance. When i run with 100mm/sec^2 acceleration - It stops halfway at 56mm 20240111_121115.jpg

When i run with 1000 - 2000 mm/sec^2 acceleration - it travels to 80mm https://github.com/programmeddeath1/webhost/blob/master/20240111_122133.jpg

When i run with 5000mm/s^2 and above till 100kmm/s^2 - it travels to 85mm https://github.com/programmeddeath1/webhost/blob/master/20240111_122519.jpg

2) The motors are not getting triggered in sync at times, it could be changes in the code setup, that might be taking up more cpu in the esp thereby affecting synchronized motor running.

For the same execution of 88mm, one motor is moving to 87mm, two are moving to 82, thereby tilting the original position of the end-effector by a small difference.

https://github.com/programmeddeath1/webhost/blob/master/20240111_120125.jpg https://github.com/programmeddeath1/webhost/blob/master/20240111_120141.jpg

what i doubt is that since it is not synchronised, the load of the motor running first might be affecting the movement of the motors moving even few thousand ms later and thus they end up in different positions. The first motor moves 87mm which is correct the other two motors are moving just a tad later and their positions are smaller.

https://github.com/gin66/FastAccelStepper/assets/44861370/b0632f37-9ba9-460c-9a82-da813068889c

gin66 commented 5 months ago

Hi. perhaps you start with a different approach: solve the problem with one motor without any load. As soon as this works, extend to three motors. If this is successful attach the load. In the moment it appears to me, that you try to debug a complex setup and you cannot be sure, that all is working properly: there could be plenty of reasons for your problems and eventually more than one: stepper driver power supply, stepper driver control settings, lost steps, friction, mechanical slippage, EMC on your endpoint switches, application code and/or even FastAccelStepper.

You ask me: Does the areMotorsAtTarget() take some time after the motors have actually stopped or is it instantaneous after the motor execution command is completed from the esp?. But this function is in your application code and you have not shown that code.

In order to get here focused on FastAccelStepper: if you believe, there is an issue, please isolate the issue on a simple setup and code base, which can be understood and reproduced from someone not at your setup. All else will likely not be successful endeavors.

programmeddeath1 commented 5 months ago

Hi i understand, ill try and isolate and test if time permits.

The function i meant I had to remove, i had to cut functions from the display because the code IP is currently private - this is the function

  return !stepper[0]->isRunning() && !stepper[1]->isRunning() && !stepper[2]->isRunning();
}

is stepper->isRunning() based purely on when the last motion command is executed? because i assume - its difficult to estimate purely from the software when the hardware has finished execution.

gin66 commented 3 months ago

stale