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

What is wrong with the PTP speed in T1 on the KSS8.7

  • Koppel
  • December 22, 2022 at 12:44 PM
  • Thread is Unresolved
  • Koppel
    Reactions Received
    19
    Trophies
    3
    Posts
    132
    • December 22, 2022 at 12:44 PM
    • #1

    Hi,


    The PTP speed in T1 mode on the KSS 8.7 is unbearably slow.

    How slow? Well let me tell you with the speed test example I run on two systems.

    From Y -300 to Y 400 so a 700 mm running distance and measured the time in T1 mode while at 100% speed on the Teach Pendent.

    System 1:
    KSS 8.6.4

    KR C4 Compact

    KR10 R1100 Agilus 2 robot (A six axis one)

    System 2:

    KSS 8.7.4

    KR C5 Micro

    KR6 R700 Z200 (A four axis scara robot)

    Code
    &ACCESS RVO1
    &COMMENT 
    DEF T1_SpeedTest ( )
    BAS(#INITMOV,0)
    
    PTP XHOME
    
    ;TEST PTP SPEED
    ;=========================
    SPTP {X 500, Y -300, Z 180}
    WAIT SEC 0
    ;Start Timer
    $TIMER_STOP[ 1 ] = TRUE
    $TIMER[ 1 ] = 0
    $TIMER_STOP[ 1 ] = FALSE
    
    PTP {X 500, Y 400, Z 180}
    ;Stop Timer
    WAIT SEC 0 ;For advance run to not stop the timer prematurely.
    $TIMER_STOP[ 1 ] = TRUE
    
    ;TEST SPTP SPEED
    ;=========================
    SPTP {X 500, Y -300, Z 180}
    WAIT SEC 0
    ;Start Timer
    $TIMER_STOP[ 2 ] = TRUE
    $TIMER[ 2 ] = 0
    $TIMER_STOP[ 2 ] = FALSE
    
    SPTP {X 500, Y 400, Z 180}
    
    ;Stop Timer
    WAIT SEC 0 ;For advance run to not stop the timer prematurely.
    $TIMER_STOP[ 2 ] = TRUE
    
    ;TEST LIN SPEED
    ;=========================
    SPTP {X 500, Y -300, Z 180}
    WAIT SEC 0
    ;Start Timer
    $TIMER_STOP[ 3 ] = TRUE
    $TIMER[ 3 ] = 0
    $TIMER_STOP[ 3 ] = FALSE
    
    LIN {X 500, Y 400, Z 180}
    
    ;Stop Timer
    WAIT SEC 0 ;For advance run to not stop the timer prematurely.
    $TIMER_STOP[ 3 ] = TRUE
    
    
    END
    Display More

    The results.

    System 1 (KSS 8.6.4)
    PTP time: 9,684 sec

    SPTP time: 3,852 sec

    LIN time: 5760 sec (Path was close to singularities so slower then necessary)

    System 2 (KSS 8.7.4)

    PTP time: 47,508 sec

    SPTP time: 3,744 sec

    LIN time: 5,964 sec

    This is nor normal and causes the programmer to test the programs in other modes which is not a safe way to avoid collisions.

    Its over ten times slower than SPTP. Why?
    Considering this was a 700mm Point to point distance... the speed was 14,7 mm/sec ...

    The speed in T1 should be limited to 250mm/s

    What is going on?

  • Go to Best Answer
  • Fubini
    Reactions Received
    278
    Trophies
    9
    Posts
    1,886
    • December 22, 2022 at 12:50 PM
    • #2

    The differnce between ptp and sptp is usually:

    Post

    RE: Manual speed difference

    Yes by switching these types you get fundamentally different solutions on how KRC treats speed reductions to be safe in T1. I have explained this for a switch from LIN to PTP in the past in the german partner forum here:

    https://www.roboterforum.de/roboter-forum/…82202#post82202

    The quick deepl translation is as follows:

    This is due to reductions like $red_t1. This is added to the override in T1. If you have programmed slow speeds in a PTP movement, it will be even slower. By the way, this is no…
    Fubini
    May 17, 2021 at 1:13 PM

    To investigate further it would be easiest to have a krcdiag of 8.6 and 8.7 to lookup what differences in relevant machine data might be.

    Fubini

  • Koppel
    Reactions Received
    19
    Trophies
    3
    Posts
    132
    • January 2, 2023 at 8:43 AM
    • #3

    I do not understand how a link to this thread gives an answer on how to solve this problem.

    This thread has another link to German version of Robot Forum.

    Fubini wrote there:

    Quote

    The quick translation is as follows:

    This is due to reductions like $red_t1. This is added to the override in T1. If you have programmed slow speeds in a PTP movement, it will be even slower. By the way, this is no longer the case with Spline. There is always limited to 250 mm/s no matter if LIN or PTP, because there are no more factors like $red_t1.

    Such general factors usually have historical reasons. In the past, PTP could not be limited to Cartesian 250 mm/s as a pure movement in the axis space. In the meantime this is possible via $speed_limit_teach_mode. But for compatibility you won't get rid of the old method as default. But you can change it somewhere ($custom.dat?). I don't remember the name of the variable, $Red_t1_ov or something like that.


    I am not able to find any parameter called $red_t1


    Can we solve this problem, as this can be safety hazard because nobody will test a program in T1 if it is not working correctly and happens on all new robots straight out of the box.
    It's not like I did something to the robot to act like that... it's how they come out of the box.

  • Fubini
    Reactions Received
    278
    Trophies
    9
    Posts
    1,886
    • January 2, 2023 at 9:35 AM
    • Best Answer
    • #4
    Quote from Fubini

    To investigate further it would be easiest to have a krcdiag of 8.6 and 8.7 to lookup what differences in relevant machine data might be.

    And the difference in machine data between the "fast" and "slow" robot is? If you do not know what you need to look at create a complete archive or krcdiag, open of both machines, unzip them and compare using e.g. kdiff3 or post both archives otherwise its difficult to guess whats configured. Morst important files to diff are r1/$robcor.dat, r1/$machine.dat and everything in the STEU folder.

    There are too many possibilities in configuration to trigger your "faulty" behavior.

    Fubini

  • Koppel
    Reactions Received
    19
    Trophies
    3
    Posts
    132
    • January 27, 2023 at 3:51 PM
    • #5

    There is a quote from Panic mode in this thread:
    BAS function speed limit is cummulative in T1 mode and much slower than 250mm/s

    Quote

    PTP is the fastest motion... and this is why in T1 mode PTP is throttled more aggressively than other types of motion.

    but in some cases there is a bug and safety controller reduces speed even further. in such case in T1 mode PTP becomes really really slow, specially when approximated with CP motions... by doing BCO you can skip that super slow part and get straight to CP motion such as LIN and robot will move normally. solution is to contact KUKA. they will tell you how to fix this (for example by changing limits in safety controller or whatever).

    I think I am also hit with this bug.

    PTP motions are limited by a reduction factor ($RED_T1*max. axis velocity).

    If the maximum axis velocity configured for T1 in the safety controller is lower than the maximum possible axis velocity $RED_T1*max., the reduction factor is automatically reduced to prevent the velocity monitoring from being triggered.

    In my STEU > MADA > MACHINE.DAT file there are.

    $RED_VEL_AXC[1]=11

    $RED_VEL_AXC[2]=8

    $RED_VEL_AXC[3]=8

    $RED_VEL_AXC[4]=10

    These values are percentages of the maximum related to these. (values are in RPM)

    $VEL_AXIS_MA[1]=5600.00

    $VEL_AXIS_MA[2]=6000.00

    $VEL_AXIS_MA[3]=5224.99707

    $VEL_AXIS_MA[4]=4975.84521

    So for example the limit for the first axis would be 11% x 5600rpm = 616 rpm.
    I can divide this by 60 seconds = 616/60 = 10,26 rounds per second.

    I can multiply this by 360° = 10,26*360 = 3696 °/sec

    In my limits in the safety configuration are:

    A1 = 30°/sec

    A2 = 30°/sec

    A3 = 250mm/sec

    A4 = 30°/sec

    Basically what I understand I need my $RED_VEL_AXC[1] * $VEL_AXIS_MA[1] to be under the 30°/sec value and if it is not then the system reduces the speeds to ridiculous levels.

    The numbers are close to a 100 times out, so I don't know if there is a massive 100:1 planetary gearbox in there somewhere or what?

  • Online
    panic mode
    Reactions Received
    1,280
    Trophies
    11
    Posts
    13,082
    • January 27, 2023 at 4:16 PM
    • #6

    you are chasing this for more than a month. why not simply contact KUKA as suggested?

    and how come A3 limit is linear when that axis is rotary?

    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

  • Koppel
    Reactions Received
    19
    Trophies
    3
    Posts
    132
    • January 30, 2023 at 7:59 AM
    • #7

    It's a Scara, thats why A3 is linear. And I did contact KUKA.

    Their responses were a little too cryptic for me and I also wanted to give something back to the community by solving it "out in the open"

  • Online
    panic mode
    Reactions Received
    1,280
    Trophies
    11
    Posts
    13,082
    • January 30, 2023 at 2:59 PM
    • #8

    oh... did not see that mentioned. what was the reply?

    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

  • Koppel
    Reactions Received
    19
    Trophies
    3
    Posts
    132
    • January 30, 2023 at 4:18 PM
    • #9

    What I wrote above was pretty much the interaction I had with KUKA.

    Quote
    If the maximum axis velocity configured for T1 in the safety controller is lower than the maximum possible axis velocity $RED_T1*max., the reduction factor is automatically reduced to prevent the velocity monitoring from being triggered.

    This explanation is hinting why sometimes the T1 speedlimits are very very slow.
    I sent them my files and they pointed out the relevant parameters and gave links to explanations of these parameters. (some xpert.kuka.com page that expires in 14 days)

    But when I manually calculated and compared the parameters (3696 °/sec vs 30°/sec) they seem way off.
    I didn't want to adjust anything just yet, rather to understand beforehand what all of that means. Because currently the maximum velocity 30°/sec is way way lower than the $RED_VEL_AXC * $VEL_AXIS_MA.

  • Online
    panic mode
    Reactions Received
    1,280
    Trophies
    11
    Posts
    13,082
    • January 30, 2023 at 5:40 PM
    • #10

    that is a hint alright but that is not a solution. whoever told you this should be moved to a different position or retrained

    you are dealing with unexpected and defective behavior of their product, so they are supposed to tell you explicitly what to do, such as "change value of A to new value B" whatever those A and B may be.

    this is not the first time this happened, they have it documented. yes you could play around with things and mess with values yourself but

    a) that is not something you are expected or supposed to do

    b) changed value is kinematics dependent (robot with longer reach have different reduction)

    c) this is something that can be a safety hazard and exceed T1 limit of 250mm/s.

    d) that need to work equally well with both motion instruction sets. manipulating value of wrong parameter may look ok for PTP bur also affect SPTP and you do not have insight into inner working of KSS.

    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

  • Koppel
    Reactions Received
    19
    Trophies
    3
    Posts
    132
    • February 9, 2023 at 8:30 AM
    • #11

    KUKA help concluded that:

    Quote

    As mentioned, this is something that probably will be fixed in the next major KSS release.

    At the moment it's recommended to use the SPTP motion. Thre is no "fix" for this at the moment.

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

Similar Threads

  • Understanding the difference between motion types

    • MNMRoboter
    • September 21, 2020 at 1:05 AM
    • KUKA Robot Forum

Tags

  • PTP speed slow KSS 8.7
  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