1. Home
    1. Dashboard
    2. Search
  2. Forum
    1. Unresolved Threads
    2. Members
      1. Recent Activities
      2. Users Online
      3. Team Members
      4. Search Members
      5. Trophys
  3. Articles
  4. Blog
  5. Videos
  6. Jobs
  7. Shop
    1. Orders
  • Login or register
  • Search
This Thread
  • Everywhere
  • This Thread
  • This Forum
  • Articles
  • Pages
  • Forum
  • Blog Articles
  • Products
  • More Options
  1. Robotforum - Support and discussion community for industrial robots and cobots
  2. Forum
  3. Industrial Robot Support and Discussion Center
  4. KUKA Robot Forum
Your browser does not support videos RoboDK Software for simulation and programming
Visit our Mainsponsor
IRBCAM
Robotics Channel
Robotics Training
Advertise in robotics
Sponsored Ads

minimum distance between points for a given speed

  • sloopkogel
  • December 15, 2024 at 10:28 AM
  • Thread is Unresolved
  • sloopkogel
    Trophies
    2
    Posts
    34
    • December 15, 2024 at 10:28 AM
    • #1

    I have a question regarding moving the robot through a lot of points, for example when using the robot for milling / plasma cutting and the robot has to follow a path created by some sort of post processor. When the points are too close to eachother (the points are too 'dense') the tool will move slower than the commanded velocity.

    For instance, this code will be executed 'normally', with the commanded velocity:

    Code
    $advance = 1
    LIN {X 0.0, Y 0.0, Z 0.0, A 0.0, B 0.0, C 0.0} C_DIS
    LIN {X 2.0, Y 0.0, Z 0.0, A 0.0, B 0.0, C 0.0} C_DIS
    LIN {X 4.0, Y 0.0, Z 0.0, A 0.0, B 0.0, C 0.0} C_DIS
    
    
    [...]
    
    
    LIN {X 96.0, Y 0.0, Z 0.0, A 0.0, B 0.0, C 0.0} C_DIS
    LIN {X 98.0, Y 0.0, Z 0.0, A 0.0, B 0.0, C 0.0} C_DIS
    LIN {X 100.0, Y 0.0, Z 0.0, A 0.0, B 0.0, C 0.0} C_DIS
    Display More


    Using this code however, the robot will move much slower:

    Code
    $advance = 1
    LIN {X 0.0, Y 0.0, Z 0.0, A 0.0, B 0.0, C 0.0} C_DIS
    LIN {X 0.1, Y 0.0, Z 0.0, A 0.0, B 0.0, C 0.0} C_DIS
    LIN {X 0.2, Y 0.0, Z 0.0, A 0.0, B 0.0, C 0.0} C_DIS
    
    
    [...]
    
    
    LIN {X 99.8, Y 0.0, Z 0.0, A 0.0, B 0.0, C 0.0} C_DIS
    LIN {X 99.9, Y 0.0, Z 0.0, A 0.0, B 0.0, C 0.0} C_DIS
    LIN {X 100.0, Y 0.0, Z 0.0, A 0.0, B 0.0, C 0.0} C_DIS
    Display More


    I have 2 questions about this behavior:

    1: Am I correct in assuming that the reason for this, is that the advance pointer cannot look ahead far enough within the cycle time of the internal clock, which I beleive is 12ms?

    2: How does one determine the minimum distance between two points before the velocity drops below the commanded velocity? If statement 1 is correct then I beleive it could be as simple as Commanded velocity / (1000 / 12) ? Or is it more complex, and is trial and error the only way to find out the minimum distance between 2 points

    I am aware that putting the motion commands in a spline block can fix this problem, but this is not possible in my case, because in my application I sometimes need the robot to start at a given point instead of the first line (this is possible in my case because I use an array of E6Pos that I loop through instead of the code provided in the example)

  • hermann
    Reactions Received
    404
    Trophies
    9
    Posts
    2,595
    • December 15, 2024 at 12:07 PM
    • #2

    Why do you set $advance to 1 ?? When you think

    Quote from sloopkogel

    1: Am I correct in assuming that the reason for this, is that the advance pointer cannot look ahead far enough within the cycle time of the internal clock, which I beleive is 12ms?

  • Fubini
    Reactions Received
    272
    Trophies
    9
    Posts
    1,872
    • December 15, 2024 at 2:38 PM
    • #3

    The problem is not the distance and velocity but the time to accelerate to the desired velocity. In case of e.g. approximation not possible you still need to be able to decelarate to velocity zero at the given target point. So in case of trapzoidal velocity profile acceleration is the limiting factor.

    In worst case the trapzoidal profile degenerates to a triangle profile. So the intersection of acceleration and decelaration phase determines the maximal reachable velocity.

    So define the velocity you want to reach. Calculate the time it needs to accelerate to this velocity and integrate twice to get the maximal distance needed to perform the deed and double the result.

    And use C_VEL and not C_DIS for blending to hold blending velocity at the maximal velocity.

    Fubini

  • sloopkogel
    Trophies
    2
    Posts
    34
    • December 15, 2024 at 5:30 PM
    • #4

    hermann , the only reason is to simplify the case for this example. This is not a real life problem I'm trying to solve, because I have edited my program to have the points spaced out far enough so that the velocity does not drop, this topic is only intended to get a better understanding of why this is necessary.


    Fubini , I do not understand, why would acceleration / deceleration be an issue? The robot does not stop / delecerate / accelerate in between the points

  • panic mode
    Reactions Received
    1,267
    Trophies
    11
    Posts
    13,033
    • December 16, 2024 at 2:07 AM
    • #5

    if you want to program robots, math should be your second nature. so why not just calculate it yourself...? does not need to be anything fancy, physcis1 course will do..

    KSS uses advance run pointer to collect motion data for motion planner. number of motion instructions that can be fetched is set by $ADVANCE and the value here is 0-5 motions. so at most it can collect data for 5 motions.

    if the motions are only 0.1mm long, this only allows motion planner to plan path for 5*0.1mm=0.5mm. in other words, robot has not idea what lies beyond those 0.5mm. maybe the next instruction is to stop so it must be ready to stop.

    btw. robot arm is not massless. it cannot be accelerated and decelerated on a dime - things like this take time and space. pick some numbers (estimates are fine) and calculate what is doable and you will see that robot is doing already pretty much on it...

    say your robot is KR60. wrist itself weight some 80kg, payload is some 50kg really close to the flange (to minimize effects of inertia) and arm is 1m long from A3 to payload. check the power of the motor and drive. suppose that arm is already moving at respectable 1m/s (at TCP), acceleration limit is set at 10m/s^2 etc. then try to do a 90deg turn on a motion segment that is perpendicular and although motion is approximated, it has small radius, such as 0.1mm.

    then try to find out how much energy/power the wrist and payload have. and how much is needed for A3 axis to make that turn... you can approximate things to get an idea. for example treat wrist mass as point mass at halfway between elbow and TCP (0.5m/s)

    hint:

    E=mv^2/2 (kinetic energy)
    P=dE/dt (power)

    at 1m/s this 0.1mm segment path would need to happen in 0.1ms and the change of direction would result in a massive acceleration.

    pretty sure that A3 motor power on a robot like this is a single digit kW (like 3 or maybe 5kW).

    but lets see what would it take to make that turn:

    E=Epayload + Ewrist = 50*(1m/s)^2/2 + 80*(0.5m/s)^2/2 = 25J+20J=45J

    P=45J/0.0001s=450000W=450kW or nearly half a Megawatt...

    so yeah... this would be pretty much as if robot arm was hit by a cannon. robot arm would be obliterated.

    btw. even if we ignore the physics, motor and drive size etc. lets see what happens with just processing of the motions. robot interpreter interpolation time is 12ms. and 0.1ms is way too short. that means that to process that turn, the fastest way is to do it is in a single interpolation cycle and for that velocity would need to be some 120x slower. so divide 1m/s by 120 and you get in the neighborhood of 8.333mm/s as an absolute maximum velocity... and that is of the robot does not make any turns. when it tries to turn, or change orientation this could get further bogged down due to acceleration/deceleration...

    1) read pinned topic: READ FIRST...

    2) if you have an issue with robot, post question in the correct forum section... do NOT contact me directly

    3) read 1 and 2

  • xianyv
    Trophies
    1
    Posts
    24
    • December 25, 2024 at 1:23 PM
    • #6

    panic mode Fubini hermann
    Do you have any KUKA documents, theoretical books or academic papers related to this topic? Thank you very much

  • Fubini
    Reactions Received
    272
    Trophies
    9
    Posts
    1,872
    • December 25, 2024 at 2:40 PM
    • #7

    I can recommend "John J. Craig: Introduction to Robotics. Mechanics and Control". But for all the math required for the above discussion basicall simple newtonian mechanics that here in Germany is teached in 9th grade is sufficient. Also look for trapezoidal velocity (second order profile) or acceleration profile (third order profile) with google. A code I can recommend for the basic planning can e.g. be found on ruckig.com and going to the free github version. There is a linked paper on this webpage.

    Furthermore there is nothing official from KUKA how the details work in their controller software. Obviousl some company secrets are involved here. I only have some advantages because until a few years ago I was affiliated with the KUKA R&D for 16 years.

  • xianyv
    Trophies
    1
    Posts
    24
    • January 10, 2025 at 3:15 PM
    • #8

    During my research, I came across a description of the KUKA trajectory planner (as shown in the attached image) which states that the planner starts generating a segment at a user-defined distance (ds) from the end configuration, and then begins applying the configuration of the next trajectory. Additionally, it mentions that this distance is limited to half the length of the previous segment.

    If this description accurately reflects the KUKA system's behavior, I would greatly appreciate your insights on how this relates to the $ADVANCE instruction and the constraints of the controller's interpolation cycle (e.g., the 12 ms cycle in KSS). Specifically, I am curious about:

    1. The interaction between the trajectory planner’s early segment generation and $ADVANCE, which controls the number of preloaded motion instructions.
    2. Whether the interpolation cycle plays a role in determining or limiting the behavior described in the image.

    Please note that my inquiry is solely academic and aimed at deepening my understanding of these mechanisms. The attached reference was independently sourced during my research and is not intended to challenge or undermine any previous explanations.

    Thank you very much for your time and guidance. I look forward to your valuable insights.

  • Fubini
    Reactions Received
    272
    Trophies
    9
    Posts
    1,872
    • January 10, 2025 at 4:16 PM
    • #9
    Quote from xianyv

    During my research, I came across a description of the KUKA trajectory planner (as shown in the attached image) which states that the planner starts generating a segment at a user-defined distance (ds) from the end configuration, and then begins applying the configuration of the next trajectory. Additionally, it mentions that this distance is limited to half the length of the previous segment.

    Yes that's correct. This is called blending or approximation. You can not blend more than half of a single motion to avoid not hitting the given curve at all.

    Quote from xianyv

    would greatly appreciate your insights on how this relates to the $ADVANCE instruction

    You need $advance of at least 1 since the controller needs to see at least the next motion instruction at planning time to insert a blending curve.

    Quote from xianyv

    the constraints of the controller's interpolation cycle (e.g., the 12 ms cycle in KSS).

    There is no constraint here. 12 ms interpolation cycle only is used when executing the previous planned motion by the motion planner. Think of it like running two parallel threads https://en.wikipedia.org/wiki/Thread_%28computing%29?wprov=sfla1. One is the the planning thread which basically is calculation of a function f(t). This planned function then is transferred to the execution thread which samples a value of f every 12 ms, so first f(0.012), next f(0.024) and so on. Each sampled value then is sent to the motors for execution.

  • Online
    SkyeFire
    Reactions Received
    1,039
    Trophies
    12
    Posts
    9,380
    • January 10, 2025 at 5:27 PM
    • #10

    Execution time per line of KRL code (for non-motion, non-blocking statements) is typically down in the single-digit nanosecond range. This allows a very large number of non-blocking statements to potentially execute in a single ~2ms time window.

    For example, while the SPS only executes once every 12ms, and only for a fraction of that 12ms period (~2ms, IIRC), a tight SPS loop can execute thousands of statements in that small time window.

    This same speed allows non-blocking commands between PTP/LIN/CIRC commands, and the advance path planner, to "stay ahead" of the active motion. The limitation on motion segments isn't processor speed, it's that the path planner can only look up to a certain number of motion ahead of the main run pointer.

    Fubini is far more knowledgable than I on the minute details, but in a general sense, the motion planning needs to see ahead of the robot's current position and velocity by a certain minimum distance in order to safely plan a blended motion. How far ahead varies depending on robot model, payload, and the current inertia&pose of the arm. Since the look-ahead is defined by the number of motion commands ($ADVANCE with a maximum of 5), crowding motions too closely together can cause the path planner to give up and "fail safe" to non-blended motion.

    There are a lot of factors in the robot that influence this. $FILTER is the one I'm most familiar with, though in other contexts. Basically, $FILTER enforces a minimum amount of time required for any motion command to execute. This is mostly to avoid having the robot shake itself to pieces by attempting to accelerate too violently -- I have done in an R&D context and nearly destroyed a KR500. So if the time to move between to consecutive points is less than $FILTER (or, possibly if the half-segment falls below $FILTER), I would not be surprised if the path planner began giving up on motion blending. I never tried that particular scenario in R&D, however.

  • xianyv
    Trophies
    1
    Posts
    24
    • January 11, 2025 at 4:47 AM
    • #11

    SkyeFire  Fubini

    Thank you very much for your detailed and comprehensive explanations regarding the KUKA trajectory planner, $ADVANCE, interpolation cycles, and related parameters. Your insights on blending, motion planning, and the role of $FILTER have been extremely helpful in deepening my understanding of how the system operates.

    If I may ask one more question: How much information (e.g., position, velocity, acceleration, etc.) can the robot's buffer hold during motion planning? Specifically, is there a fixed limit or a configurable parameter that determines the size of this buffer, and how does this affect the trajectory planner’s ability to handle complex or densely spaced path points?

    Thank you again for your time and expertise. I truly appreciate your guidance and look forward to learning more from you.

  • Fubini
    Reactions Received
    272
    Trophies
    9
    Posts
    1,872
    • January 11, 2025 at 6:22 AM
    • #12

    The actual robot controller where planning and execution take place resides in a ramdisk and is implemented inside a VxWorks real time operating system. Only limitation is the reserved memory for program store, calculutions, execution and other necessary stuff inside the ramdisk. So this memory is shared by many different tasks and only actively monitored for memory overflow. There is no specific borders for specific tasks just shared memory. There are limitations on how much memory can be adressed that are not Kuka made but VxWorks. If I remember correctly this overall bound was 384 MB in the last controller versions I was involved with before leaving Kuka a few years ago. This bound can not be tweaked. Often users are suprised that increasing the controller ram does not improve how many programs can be stored on the controller because they are not aware of the dual os architecture Windows/VxWorks used and the ramdisk. Memory partitions inside the VxWorks ramdisk can be tweaked by kuka experts a little bit but not much. You can for example shift a little bit of memory reserved for VxWorks OS to user space to increase the memory you can use for program store, calculation and execution.

    You can find more in this direction by using VxWorks keyword in forum search.

  • Online
    SkyeFire
    Reactions Received
    1,039
    Trophies
    12
    Posts
    9,380
    • January 13, 2025 at 1:10 PM
    • #13
    Quote from xianyv

    If I may ask one more question: How much information (e.g., position, velocity, acceleration, etc.) can the robot's buffer hold during motion planning? Specifically, is there a fixed limit or a configurable parameter that determines the size of this buffer, and how does this affect the trajectory planner’s ability to handle complex or densely spaced path points?

    In KSS, the Advance Run Pointer only looks ahead by a fixed number of motion commands, between 0 and 5 (set by $ADVANCE). Anything further ahead is ignored until the robot physically completes the current motion in the queue. That's the only adjustment of the look-ahead buffer that I'm aware of. The buffering is unaffected by path complexity or point spacing. It's the motion planning and execution that can be affected.

Advertising from our partners

IRBCAM
Robotics Channel
Robotics Training
Advertise in robotics
Advertise in Robotics
Advertise in Robotics

Job Postings

  • Anyware Robotics is hiring!

    yzhou377 February 23, 2025 at 4:54 AM
  • How to see your Job Posting (search or recruit) here in Robot-Forum.com

    Werner Hampel November 18, 2021 at 3:44 PM
Your browser does not support videos RoboDK Software for simulation and programming

Tag Cloud

  • abb
  • Backup
  • calibration
  • Communication
  • CRX
  • DCS
  • dx100
  • dx200
  • error
  • Ethernet
  • Ethernet IP
  • external axis
  • Fanuc
  • help
  • hmi
  • I/O
  • irc5
  • IRVIsion
  • karel
  • kawasaki
  • KRC2
  • KRC4
  • KRC 4
  • KRL
  • KUKA
  • motoman
  • Offset
  • PLC
  • PROFINET
  • Program
  • Programming
  • RAPID
  • robodk
  • roboguide
  • robot
  • robotstudio
  • RSI
  • safety
  • Siemens
  • simulation
  • SPEED
  • staubli
  • tcp
  • TCP/IP
  • teach pendant
  • vision
  • Welding
  • workvisual
  • yaskawa
  • YRC1000

Thread Tag Cloud

  • abb
  • Backup
  • calibration
  • Communication
  • CRX
  • DCS
  • dx100
  • dx200
  • error
  • Ethernet
  • Ethernet IP
  • external axis
  • Fanuc
  • help
  • hmi
  • I/O
  • irc5
  • IRVIsion
  • karel
  • kawasaki
  • KRC2
  • KRC4
  • KRC 4
  • KRL
  • KUKA
  • motoman
  • Offset
  • PLC
  • PROFINET
  • Program
  • Programming
  • RAPID
  • robodk
  • roboguide
  • robot
  • robotstudio
  • RSI
  • safety
  • Siemens
  • simulation
  • SPEED
  • staubli
  • tcp
  • TCP/IP
  • teach pendant
  • vision
  • Welding
  • workvisual
  • yaskawa
  • YRC1000

Tags

  • SPEED
  • cnc
  • velocity
  • approximation
  • G-code
  1. Privacy Policy
  2. Legal Notice
Powered by WoltLab Suite™
As a registered Member:
* You will see no Google advertising
* You can translate posts into your local language
* You can ask questions or help the community with your knowledge
* You can thank the authors for their help
* You can receive notifications of replies or new topics on request
* We do not sell your data - we promise

JOIN OUR GREAT ROBOTICS COMMUNITY.
Don’t have an account yet? Register yourself now and be a part of our community!
Register Yourself Lost Password
Robotforum - Support and discussion community for industrial robots and cobots in the WSC-Connect App on Google Play
Robotforum - Support and discussion community for industrial robots and cobots in the WSC-Connect App on the App Store
Download