-
Notifications
You must be signed in to change notification settings - Fork 691
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
What's the proper way to code movement command with RPDO? #585
Comments
Hi Willy,
My first remark is that you need to tune your network driver. It takes more than 300us for a packet to return to the master. Probably your driver is doing packet coalescing. Use ethtool to figure out and optimize the settings. My second remark is that in almost all cases it is wise to update the PDO data in the real-time task and not in the standard task as you are currently doing. Control loops and their code are real-time, so they belong in a real-time task. When you transfer data between two tasks you need to synchronize or protect you data. If you write data in your main task it could get interrupted by the real-time task just in the middle. So then it will send out PDO data that is half new and half old data. That is probably not what you want. SOEM does not do intertask-communication, but you can run your own code or use one of the many libs specially written for this. Of course all of these problems disappear when you run the control code in the same real-time task as the PDO transfer.
First remark is that you use different data types for move_ and PositionActualValue. Try to avoid that, although in this case it does not matter. But in general be accurate with types, because automatic conversions by the compiler will byte you sometimes. Second remark is that the code actually does what you have written (and again not what you intended). You read PositionActualValue from the PDO buffer. But this value is read 200 times is rapid succession (takes less than 1us). In that time the value does not change as the PDO cycle time is 4000us. When you copy the move_ buffer to the TargetPosition time has passed and PositionActualValue has changed. Move_ has not changed. So you will have a very different result when doing output_TargetPosition = input_positionValue + movement.
|
Hi Arthur, |
I think the
The total transfer time from master through all slaves and back again to the master is the total slave delay plus the length of the packet At 100Mb/s one byte takes 80ns. Each metre of cable adds 5ns of delay. So in your case a rough estimate is (96 * 80ns + 6 * 300ns + 6 * 1m * 5ns) = 9510ns. This is wire time. Off course what wireshark sees is this plus the time spend in the network driver. In your case 300us - 9.5us = 290us is an awful lot of time to spend in a network driver. Therefore (and from years of experience) I assume there is some interrupt coalescing going on. This is done in many drivers to limit the number of interrupts in your PC. For TCP/IP throughput this does not matter but for real time protocols like EtherCAT this is killing. This also explains why you would see two packets being send in short succession and then a wait and then the reception of both packets. When the driver receives the first packet back it simply waits. Then the second packets comes in and the driver waits. Only when a timeout value has passed the driver transfers the packets to the network stack. Only then they are seen by wireshark (and get timestamped) and soem.
The clever way of handling timing in a non blocking way is to use state machines in your code. Use the "tick"of your real-time loop to increment the state. Wiki is your friend here.
|
Hi Arthur, |
|
Hi Arthur, 2.The second problem here is the most confusing one, I wrote some quick testing code to send movement command to the output buffer, and checked on the packets, I noticed the packet is actually updating the data I wrote every cycle. But the weird thing is the data just didn’t get execute by the slave. |
For proper way of getting DC and sync working see: To distribute clocks you have to use FRMW (read-multiple-write) and not FPWR (write). You read the clock from the first reference slave and write it to all others. For your drive control problem I can not help you without knowing something about your slaves. What is the brand and type? Where can I find the datasheet? How did you configure the slaves? I am no wizard with a crystal ball. |
Hi Arthur, |
As far I could read from the datasheet the only supported modes under EtherCAT control are CSP, CSV and CST. The other modes are next to useless. As these modes are cyclic synchronous this means there is no buffer in the slave. Your application needs to calculate the correct setpoints for your trajectory and output them to the slave at the exact moment in time they need to be executed. This is not a disadvantage, you gain the best possible control in exchange for a bit more complicated programming on the master side. My advice is to use CST mode, and run the velocity, and optionally position control loop, on the master side. Only very few applications need the extra bandwidth that is possible by running these on the slave. Rule of thumb, calculate your mechanical time constant, multiply by 5 to have position loop speed, multiply by 5 to get velocity loop speed. So for example if your mechanical time constant is 10hz, the position loop runs at 50hz and the velocity loop at 250hz. Anything more and you are just amplifying noise. |
Hi Arthur, |
|
Hi Arthur, |
Ahh, now I get what you where asking! Yes indeed the slave does not respond the way it is supposed to. After the slave acknowledges OP state (packet #63384) it takes almost exactly 100ms before the LRD packets return data with a positive workcounter (packet #63497). This is actually wrong for 2 reasons.
|
Hi Arthur, |
Hi Arthur, Please take a look at those two files, one file recorded the Slave's Clock stabilization in the Pre-op mode, and the Packet Cycle jitter data in the Op mode; another file is the corresponding source code tsee if the way i captured data has any flaws in the first place. Thanks in advance. |
@ArthurKetels And apart from that, i found out another very interesting thing about how did my Ethercat driver take/ignore the data from the packets that i really want to share with you, it behaves so wrong yet so amazingly consistent that i must missed something here. I willy update my discovery and the evidence here when you got time to read them. Please let me know when you have time to continue the discussion. Have a good one! |
On one side expected behavior, on the other side you have be precise in your measurements. Plus minus 100us jitter is to be expected without taking special precautions. You can read on this effects by other users here, improvements of 10x are no exception with a bit of tweaking. W.r.t. your code. You add an extra packet in the rt-loop: The other thing is that you have to watch out using C++ constructs like vector<>. They can have unbounded latency because they invoke memalloc. If you want to use them at least preallocate with .reserve(). As a last remark, for cycle rates of 4ms your jitter of +-100us is probably good enough. Perfect is often the enemy of the good. About my available time here, it depends. I am interested in good discussions, and I respect efforts made by you and others like you. But I also have a very busy job (running two companies) and can make no guarantees. |
Hi Arthur, |
Here it comes the second part. |
It is very difficult to follow your tests. It is easier for me to understand when you make graphs of your measured data. And I do not really enjoy working through thousands of lines of wireshark captures. This is not about low level EtherCAT protocol where wireshark is certainly handy. What I propose is that you do an impulse test in CST mode. Position control is always a bit difficult to interpret, torque is much easier.
|
Hi Arthur, Yes you are right about the difficulty of interpret CSP mode data. And after i dug deepper into it i now gradually realized why you suggested me to go with CST rather than CSP, because that way you have direct control on acceleration, and with that acceleration you can easily conclude whether the position command you send in this cycle will be reached by motor in next cycle. Dumb I am, i totally neglected the physical limit of the motor, so now what i'm going to do is i will still run another several rounds of test in CSP mode to see if position-not-reached issue is actually due to the physical limit, if it is then i will then head to the CST test. The procedures you suggested there are very clear and reasoning, but since all of the motors are assembled on the mechanical housing, and they weigh over 260kg, so i think choose one slave and running them back and forth will have the effect, right? Meanwhile i will try to write the torque controller for my position control, will get back to you as soon as it gets done. Again, thanks very much. |
@ArthurKetels |
It is impossible for me to say something useful regarding your question. What you observe is what you observe. Why this is so it is difficult to answer without internal knowledge of the firmware. It is rarely so that a vendor will intentionally delay actions in a control loop. Mostly they are a side effect of design decisions. Some general information about servo control. The only thing physically controlled is the torque of the motor. The resulting velocity and position are a side effect of that torque acting on resistance and inertia of the load. Velocity is controlled by placing a secondary control loop on top of the torque controller. Position in turn is controlled by a control loop on top of the velocity controller. This is all well known. There is a problem however when you are changing velocity in discrete time steps (as in CSV mode). How should the controller know how much torque it should apply at the end of the time step? There are an infinite number of solutions. Still the controller has to pick one. What if the controller assumes the end velocity should be steady state (no change in velocity after reaching the target velocity) but the user increases the new target setpoint (acceleration)? Then the applied torque would be too low and jumps in torque will happen. The opposite happens when requesting deceleration. The CSP mode (position control) will make it even worse. Should the controller aim for zero velocity after reaching the target setpoint? And should the torque be zero too? It is clear that the controller will never make the correct decisions when it does not know all parameters of the trajectory. And CSV and CSP modes simply do not provide enough information. That is why I do not recommend them. They seem nice on the surface, but get you into trouble very quickly. Now, how could vendors of servo drives try to get a reasonable solution to the above problems? The simplest solution is to try to figure out what the user wants in the future. Or better, wait a couple of cycles before calculating a trajectory. If you wait one cycle you can do linear interpolation, if you wait two you can co quadratic, etc. So for example your servo drive can do 4 cycles delay to figure out the trajectory you want to run. Your motor will still move synchronous to your commanded setpoints but with latency. Is there a way to avoid this lack of information problem? Well yes, with CST. The servo drive has no ambiguity anymore and can follow your setpoints without delay. Your application calculates the trajectory and knows the instantaneous velocity and position at any moment in time. From there you can control the optimal torque and send it to the drive. The above comes with one mayor caveat, is torque the lowest level of control? Actually it is not. For any smooth movement we also need to control jerk. And this means even CST is not the optimum control mode. We would like to control the derivative of torque too (jerk). Luckily the inertia of many practical servo implementations will filter out the step like changes in torque. This is true as long the cyclic update rate of torque is much higher than the mechanical inertia. A nice benefit of jerk control is that it will also reduce mechanical vibrations in your application by a large amount. High end servo controls that need high dynamic range not only employ jerk but also snap control. |
Hi Arthur, I'm sorry this is a little deviated from the gist of Soem now, but since you are probably the best one i know online who knows what's he talking about control in general, i will certainly keep update in here to see where it ends. Be well and stay safe, catch up with you next time. |
Happy to be of service. But I now close this thread. You can open an other one when you have new information to share. |
Hi all,
Hope you guys are all safe and doing well.
I have several questions regarding using Soem library and would be really grateful to get any help from here, thanks in advance.
1.Background info
After creating the output and input buffer with ec_config_map() function, I ensured ①RPDO and TPDO are what we chose ; ②the objects mapped to the PDO are correct;③the buffer size is correct(both checked the Obytes and Ibytes), and the buffer address offset is inline with Obytes and Ibytes. And then we casted the output and input buffer to our struct so that we can write data to the buffer.
2.Problems
1.Position command kept repeating
The problem here is that when we write a series of different command position to the output buffer, we were sometimes repeating the same command position multiple times then it went to the next, this is verified by the data we captured in wireshark, i send position command to slave 6 and then read the the third to sixth bytes of the last 16 bytes in wireshark.
It's a little bit counter-intuitive to me, as i thought the purely writing part would be so much faster, since ec_send_processdata() needs to construct the datagram and frame header stuff, so it would make more sense if the data we see from the buffer is overwritten by the program.
But if we use while loop, it works prefectly, whereas i want to get rid of while loop.
2.Any certain rules about writing data to output buffer?
Another weird situation is that if i send command like output_TargetPosition = input_positionValue + movement; it works; but if i create a vector/array beforehand like movement[ ] = input_positionValue and then send command like this : output_TargetPosition = movement[ i ], it doesn't work.
This is a little bit confused to me, because as far as i understand, function receive_processdata() is just one part of send_processdata(), LRD FRMW and LRW are all started from send_processdata(), i think after we created buffer, send_processdata will constantly check the input and output buffer no matter there's real data or not.
So in my opinion, those two ways of sendind command should makes no difference, cause the program is constantly checkin the buffer, you don't need to explicitly use input_positionValue to "tell" them that.
3.The order of config_dc() and config_map() matters?
From what i read, config_map() should be executed before config_dc(), because as both the EtherCat poster and the technology overview indicates: for static DC drift, we might want to do 15000 of frames transfer with FRMW command, but when we use send_processdata to do that we need to have PDO mapping finished.
But in my case, if we move config_dc() after config_map(), it just didn't work great; I don't get it either.
Here two attachments are my code and the data captured from Wireshark.
dataCaptured.zip
main.zip
The text was updated successfully, but these errors were encountered: