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

Program with massive number of programmed motions/locations

  • tlambrop
  • November 7, 2016 at 9:04 PM
  • Thread is Resolved
  • tlambrop
    Trophies
    3
    Posts
    59
    • November 7, 2016 at 9:04 PM
    • #1

    Hi all,

    KRC4, KSS 8.3

    I have a need to send my robot controller anywhere between 500k to 5 million data points to move to in a single "run." Currently I do not have DirLoader. The motions would be relatively basic motions; essentially I am just programming a raster movement where I step over in one axis ~0.5mm for each point, but at each point the feed rate (or velocity of the tool) changes.

    Currently I am looking into the RobotSensorInterface and the KRC4 EthernetIP add-ons (my robot already has these add-ons purchased) in order to transfer this amount of data real-time to the controller. Would either of these two packages possess the capability I am looking for?

    The main reason for this is that I cannot create 50-200 run time AXIS variables each with size 2^15.

    Another round-about method I am trying is creating a very large text file offline, then uploading that to a shared directory. I will open the file, read the first line in, and while that motion is being executed, I will read in the next line via the line look ahead functionality (currently I have this parameter set to 5 lines ahead). I do not know if this will work yet, but I am currently trying to test it. Does anybody know if the "look ahead" functionality applies to SREAD/SWRITE commands in addition to motion commands?

    If I have not been clear in what I am looking for, please let me know and I will try to explain it in a more clear method.

    Thanks!

  • Online
    SkyeFire
    Reactions Received
    1,040
    Trophies
    12
    Posts
    9,380
    • November 7, 2016 at 10:45 PM
    • #2

    That's a LOT of points. You're going to be at risk of exceeding the total memory limit of the /R1 tree, in addition to individual module-size limitations.

    RSI... might do what you want, but it's more intended for realtime control of motion from sensor inputs. EIP would probably be a better choice, as long as your remote EIP source can keep up with the demand.

    Reading from a massive external text file is an option, although you might need to put the Read commands into TRIGGER functions to ensure nothing breaks the advance run pointer.

    The main issue here, whatever means you use, is that your input of point data must stay some number of points ahead of the motion pointer. For example, with the default $ADVANCE value of 3, to move smoothly from Point A to B to C to D, you would have to have D's value already set before the robot began the motion from A to B. You can reduce this by reducing $ADVANCE to 1, but even then you would still have to have C loaded before the robot reached the approximation radius of B, at minimum.
    Bottom line, in order to perform approximate motion around a point, the robot must have all the points within range of the Advance pointer already known. IN the ABCD example, if D's position was still being loaded when the robot departed A, the robot would end up coming to a complete, though brief, halt at C, even if D's position had finished loading before the robot even reached B. The root of this is the way that the robot pre-calculates its path through the range of the Advance pointer (which can range from 0 to 5, but 0 is the same as turning approximation off entirely).

    You might be able to establish a "ring buffer" of sorts where the points are loaded with minimal footprint in robot memory. Something vaguely like this:

    Code
    ; preload
    FOR PointIndex = 1 TO PointArrayLimit
      ArrayIndex = PointIndex
      PointArray [ArrayIndex] = LoadRemotePoint (PointIndex) ; get point X data from remote source
    ENDFOR
    ArrayIndex = 1
    REPEAT
      PTP PointArray[ArrayIndex] C_PTP
      ArrayIndex = ArrayIndex + 1
      IF (ArrayIndex > PointArrayLimit) THEN
        ArrayIndex = 1
      ENDIF
      CONTINUE
      PointArray[ArrayIndex] = LoadRemotePoint (PointIndex) ; get point X from remote source
      PointIndex = PointIndex + 1
    UNTIL PointIndex = LastPoint
    Display More

    Something along those lines. I've probably botched something there, but it's just off-the-cuff concept code. Plus, the best way to get responses on this forum is to post bad code. :away:

    The LoadRemotePoint subroutine would be what needs to take place enough points "ahead" of the motion pointer to ensure that any expected time lags don't last long enough for the motion pointer to catch up. The preload of the array is just to ensure that the first few motions are smooth, rather than stop&go. In the robot, you might declare an E6AXIS or E6POS array of 5, or 10, or even 100, and the robot would just keep running through that array, with the remote-load staying some number of points ahead of the motion pointer, and both of them rolling over from the top of the array to the bottom. The remote-load could be an EIP I/O exchange, a read from a text file, or any of quite a few other options.

  • tlambrop
    Trophies
    3
    Posts
    59
    • November 16, 2016 at 10:45 PM
    • #3

    Thank you for the advice!

    I actually was able to find a way to condense the data I need to send so that all my feed rate variables are stored in 8 30,000 length REAL arrays. I pre-load all of my data points before proceeding to execute a motion path. My next question is in reference to the advance run pointer and if it "looks ahead" even in FOR loops and things of that nature. For example, here are two types of commands I am testing to see if A) the motion is smooth between all FOR loops, and B) do they take the same amount of time?

    FOR R = 1 TO 100
    SLIN_REL{X 1.0} WITH $VEL.CP = FEEDRATEARRAY[R] C_DIS
    ENDFOR

    VS

    FOR R = 1 TO 25
    SLIN_REL{X 1.0} WITH $VEL.CP = FEEDRATEARRAY[R]
    ENDFOR

    FOR R = 1 TO 25
    SLIN_REL{X 1.0} WITH $VEL.CP = FEEDRATEARRAY[R]
    ENDFOR

    FOR R = 1 TO 25
    SLIN_REL{X 1.0} WITH $VEL.CP = FEEDRATEARRAY[R]
    ENDFOR

    FOR R = 1 TO 25
    SLIN_REL{X 1.0} WITH $VEL.CP = FEEDRATEARRAY[R]
    ENDFOR


    So my questions, once again:

    A) Should the two "tests" I am running (one long for loop vs 4 shorter for loops) take the same amount of time?
    B) Will the motion path remain smooth in the 4 FOR loop example?
    C) (Related to question B), Does the advance run pointer look ahead for motions within for loops? So on the last motion of my first FOR loop will the ensuing first motion of my second FOR loop be smooth?

    Thank you!

  • Online
    SkyeFire
    Reactions Received
    1,040
    Trophies
    12
    Posts
    9,380
    • November 17, 2016 at 2:55 PM
    • #4

    First off, Spline motions are... odd. I can't say for certain how they'll interact with the Advance pointer, as their behavior has been changed substantially since I last used them.
    Also, pretty sure you can't use C_DIS with them, it needs to be... C_SPL?

    Speaking more generally, the Advance pointer looks ahead by a number of motions. Hence, you could have:

    Code
    LIN P1 C_DIS
    LIN P2 C_DIS
    LIN P3 C_DIS
    LIN P4 C_DIS
    FOR I = 1 TO 1000000000
      Counter = Counter + 1
    ENDFOR
    LIN P5

    And that (ridiculous) 1-million count FOR loop would execute on-the-fly, beginning when the TCP passed point P2 (assuming factory-default $ADVANCE value of 3). Assuming, of course, that there wasn't anything inside the FOR loop that would break the advance pointer (WAITs, $IN/$OUT commands, etc). I'm not... entirely certain what would happen if that FOR loop just took longer to execute than the travel time from P2 to P5, but since single-line KRL execution generally takes, IIRC, 50ns on a current-gen KRC4, it's unlikely to be an issue. At worst, you'd get an error message that "Motion could not be approximated" and the robot would probably perform a stop-and-go at P4. And if I was concerned about that, I'd use a TRIGGER-called subroutine or the SPS. This is a deliberately ridiculous example.

    If you're executing motions inside a FOR loop, the same rule still holds. Assuming $ADVANCE==3, then:

    Code
    Counter = 0
    FOR I = 1 TO 100
      LIN PointArray[I] C_DIS
      Counter = Counter + 1
    ENDFOR


    When the robot is physically executing the motion to PointArray-1, the value of Counter will already be 2, because the Advance pointer will have pre-loaded 3 motions in advance (1, 2, and 3), and pre-executed any logic in between them. The Advance pointer will get "hung" on PointArray-3 (thus not reaching the line that would increment Counter to 3) until the motion pointer reaches its transition point between PointArray-1 and PointArray-2 (generally the point of closest approach to PointArray-1). As soon as the motion pointer transitions from PointArray-1 to -2, the Advance pointer will increment Counter to 3 and get "hung" pre-loading the motion for PointArray-4.

    Note: in general, depending on an exact relationship between the Motion and Advance pointers is a bad idea -- that's why, in my original example, I pre-loaded enough of the array to guarantee that, unless a very long delay in the Remote-Load subroutine occurred, there would always be a very comfortable margin between the two pointers.

  • wes_mcgee
    Reactions Received
    1
    Trophies
    4
    Posts
    271
    • November 17, 2016 at 3:16 PM
    • #5

    This might work with SLIN but SLIN stops the motion at the end of move anyway. And its not going to work with a spline block, as that has to be preplanned completely(and in my experience maximum 800-1000 points or crashes entire controller). Interesting ideas though, would love to hear if they work.

    You mentioned EIP, I always thought of this as simply a communication protocol, versus say the native ethercat. Would the same approach be possible with ethercat, or does the EIP option package have some other advantages? If FeedRate can be declared in the Config.Dat, maybe there is a way to simply update that variable via Submit. For example we have a FRAME mapped where we can change the base via PLC (you could do this with RSI). Of course to make it active it has to be assigned in the SRC, but you are already doing that in the WITH $VEL.CP = FEEDRATEARRAY. The key would be making sure its updated fast enough in the SPS. Not to mention syncing with the PLC to make sure its on the right feed value.

  • tlambrop
    Trophies
    3
    Posts
    59
    • November 17, 2016 at 4:32 PM
    • #6

    Does SLIN stop motion at the end of the move? I thought that if I included a C_DIS or a C_SPL (still have to figure out which is the correct one to use) that it will perform a continuous path between my points?

  • tlambrop
    Trophies
    3
    Posts
    59
    • November 17, 2016 at 4:36 PM
    • #7

    For any of those interested:

    This is from the "KUKA System Software 8.3 Operating and Programming Instructions for System Integrators" manual:

    In System Software 8.2 and earlier, the identifier for approximate positioning
    with spline was “C_DIS”. If programs based on 8.2 or older
    versions are used in 8.3 and contain C_DIS, this can be retained and
    does not have to be changed to C_SPL.

  • Online
    SkyeFire
    Reactions Received
    1,040
    Trophies
    12
    Posts
    9,380
    • November 17, 2016 at 5:51 PM
    • #8

    Hm. Interesting. The manual seems to suggest that at least some of the SPL type motions can be used outside of a predefined SPLINE block, but I've never had occasion to try this. I'll have to see if I have an opportunity in the near future.

  • wes_mcgee
    Reactions Received
    1
    Trophies
    4
    Posts
    271
    • November 17, 2016 at 7:21 PM
    • #9

    You can definitely use SLIN outside a spline block. Sucessive SLIN blocks stops at the end of the move in my experience(SLIN-SPL-SLIN will move continuous though); the C_DIS command is only relevant when the next move after SLIN is LIN/CIRC such that it will approximate the last SLIN. But to be honest, I am not sure if I ever tried two successive SLIN moves with C_DIS set on both, so maybe I will need to give that a try.

  • TillEmAll
    Trophies
    3
    Posts
    1
    • April 10, 2019 at 9:37 AM
    • #10

    Hello everyone,

    I am sorry to revive this old topic. I am trying to do exactly the same as the OP: Use EthernetKRL or RSI (our robot has both, KRC 4 v8.3) to "stream" millions of points to the robot. My idea was to read the points from an external computer using the submit interpreter and write them into an array to store a fixed maximum number of points (maybe 100). Then in the KRL interpreter I would read the points from the array in a loop. By sending the current position ID to external computer the external program would know which positions have been processed. I would then continuously overwrite already processed points from the array and read in new ones, essentially creating a "ring buffer" of some sort.

    Pseudo code:

    Code
    Submit Interpreter:
    ;read operation
    ;Read message from external computer
    ReadEthernetKRL(positions_from_ext)
    ReadEthernetKRL(lastpositiontreached)
    ;Store positions in array: 
    IF lastpositiontreached = FALSE
      FOR N = 1 TO "number of positions received"
        ID = positions_from_array[N].ID
        positions_array[ID] = positions_from_ext[N].position
      ENDFOR
    ENDIF
    ;send operation
    ;Send current position ID to external computer
    SendEthernetKRL(current_position_ID)
    
    
    KRL:
    WHILE lastpositionreached = FALSE
      FOR ID = 1 TO SIZE(positions_array)
        current_position_ID = ID
        LIN positions_array[ID].position C_DIS
      ENDFOR
    ENDWHILE
    Display More

    Would something like this be possible (without breaking the advance run)?

  • Online
    SkyeFire
    Reactions Received
    1,040
    Trophies
    12
    Posts
    9,380
    • April 12, 2019 at 11:08 PM
    • #11

    I'm fairly certain that the EKI commands break the Advance Run Pointer, so doing this in the level 1 interpreter wouldn't be easy. You might have better luck doing the communications portion from the SPS.

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
  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