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

Idea for slowing down robot, when PLC sends trigger signal over ProfiNet.

  • ChristianLiinHansen
  • May 12, 2022 at 9:37 PM
  • Thread is Unresolved
  • ChristianLiinHansen
    Reactions Received
    3
    Trophies
    2
    Posts
    37
    • May 12, 2022 at 9:37 PM
    • #1

    Hi out there.

    I want to run two interrupts, triggered over ProfiNet at $IN[401]. When signals go TRUE, the robot should ramp down in speed, wherever it is, and stop within like say 2-3 sec. And when signal is FALSE, the robot should ramp up again. My idea was as followed in this test program below, where I declare the interrupts as below:

    Code
       INTERRUPT DECL 30 WHEN $IN[401] == TRUE DO ISR_SlowSpeedTestTrue()
    
       INTERRUPT DECL 31 WHEN $IN[401] == FALSE DO ISR_SlowSpeedTestFalse() 

    Full test program:

    Code: SlowSpeedTest.src
    &ACCESS RVP
    
    &REL 16
    
    &PARAM EDITMASK = *
    
    &PARAM TEMPLATE = C:\KRC\Roboter\Template\vorgabe
    
    &PARAM DISKPATH = KRC:\R1\Program\HelperFunctions
    
    DEF SlowSpeedTest( )
    
       
    
       $ADVANCE = 1
    
       INTERRUPT DECL 30 WHEN $IN[401] == TRUE DO ISR_SlowSpeedTestTrue()
    
       INTERRUPT DECL 31 WHEN $IN[401] == FALSE DO ISR_SlowSpeedTestFalse() 
    
    
    
       LOOP
    
          
    
       INTERRUPT ON 30 ; Enable the interrupt
    
       INTERRUPT ON 31 ; Enable the interrupt
    
       
    
    ;FOLD SPTP P1 CONT Vel=100 % PDAT1 Tool[1]:ForkCenterOfBoxCAD Base[5]:PalletAligned ;%{PE}
    
    ;FOLD Parameters ;%{h}
    
    ;Params IlfProvider=kukaroboter.basistech.inlineforms.movement.spline; Kuka.IsGlobalPoint=False; Kuka.PointName=P1; Kuka.BlendingEnabled=True; Kuka.MoveDataPtpName=PDAT1; Kuka.VelocityPtp=100; Kuka.VelocityFieldEnabled=True; Kuka.ColDetectFieldEnabled=True; Kuka.CurrentCDSetIndex=0; Kuka.MovementParameterFieldEnabled=True; IlfCommand=SPTP
    
    ;ENDFOLD
    
    SPTP XP1 WITH $VEL_AXIS[1] = SVEL_JOINT(100.0), $TOOL = STOOL2(FP1), $BASE = SBASE(FP1.BASE_NO), $IPO_MODE = SIPO_MODE(FP1.IPO_FRAME), $LOAD = SLOAD(FP1.TOOL_NO), $ACC_AXIS[1] = SACC_JOINT(PPDAT1), $APO = SAPO_PTP(PPDAT1), $GEAR_JERK[1] = SGEAR_JERK(PPDAT1), $COLLMON_TOL_PRO[1] = USE_CM_PRO_VALUES(0) C_Spl
    
    ;ENDFOLD
    
    ;FOLD SPTP P2 CONT Vel=100 % PDAT2 Tool[1]:ForkCenterOfBoxCAD Base[5]:PalletAligned ;%{PE}
    
    ;FOLD Parameters ;%{h}
    
    ;Params IlfProvider=kukaroboter.basistech.inlineforms.movement.spline; Kuka.IsGlobalPoint=False; Kuka.PointName=P2; Kuka.BlendingEnabled=True; Kuka.MoveDataPtpName=PDAT2; Kuka.VelocityPtp=100; Kuka.VelocityFieldEnabled=True; Kuka.ColDetectFieldEnabled=True; Kuka.CurrentCDSetIndex=0; Kuka.MovementParameterFieldEnabled=True; IlfCommand=SPTP
    
    ;ENDFOLD
    
    SPTP XP2 WITH $VEL_AXIS[1] = SVEL_JOINT(100.0), $TOOL = STOOL2(FP2), $BASE = SBASE(FP2.BASE_NO), $IPO_MODE = SIPO_MODE(FP2.IPO_FRAME), $LOAD = SLOAD(FP2.TOOL_NO), $ACC_AXIS[1] = SACC_JOINT(PPDAT2), $APO = SAPO_PTP(PPDAT2), $GEAR_JERK[1] = SGEAR_JERK(PPDAT2), $COLLMON_TOL_PRO[1] = USE_CM_PRO_VALUES(0) C_Spl
    
    ;ENDFOLD
    
    ;FOLD SPTP P3 CONT Vel=100 % PDAT3 Tool[1]:ForkCenterOfBoxCAD Base[5]:PalletAligned ;%{PE}
    
    ;FOLD Parameters ;%{h}
    
    ;Params IlfProvider=kukaroboter.basistech.inlineforms.movement.spline; Kuka.IsGlobalPoint=False; Kuka.PointName=P3; Kuka.BlendingEnabled=True; Kuka.MoveDataPtpName=PDAT3; Kuka.VelocityPtp=100; Kuka.VelocityFieldEnabled=True; Kuka.ColDetectFieldEnabled=True; Kuka.CurrentCDSetIndex=0; Kuka.MovementParameterFieldEnabled=True; IlfCommand=SPTP
    
    ;ENDFOLD
    
    SPTP XP3 WITH $VEL_AXIS[1] = SVEL_JOINT(100.0), $TOOL = STOOL2(FP3), $BASE = SBASE(FP3.BASE_NO), $IPO_MODE = SIPO_MODE(FP3.IPO_FRAME), $LOAD = SLOAD(FP3.TOOL_NO), $ACC_AXIS[1] = SACC_JOINT(PPDAT3), $APO = SAPO_PTP(PPDAT3), $GEAR_JERK[1] = SGEAR_JERK(PPDAT3), $COLLMON_TOL_PRO[1] = USE_CM_PRO_VALUES(0) C_Spl
    
    ;ENDFOLD
    
    ;FOLD SPTP P4 CONT Vel=100 % PDAT4 Tool[1]:ForkCenterOfBoxCAD Base[5]:PalletAligned ;%{PE}
    
    ;FOLD Parameters ;%{h}
    
    ;Params IlfProvider=kukaroboter.basistech.inlineforms.movement.spline; Kuka.IsGlobalPoint=False; Kuka.PointName=P4; Kuka.BlendingEnabled=True; Kuka.MoveDataPtpName=PDAT4; Kuka.VelocityPtp=100; Kuka.VelocityFieldEnabled=True; Kuka.ColDetectFieldEnabled=True; Kuka.CurrentCDSetIndex=0; Kuka.MovementParameterFieldEnabled=True; IlfCommand=SPTP
    
    ;ENDFOLD
    
    SPTP XP4 WITH $VEL_AXIS[1] = SVEL_JOINT(100.0), $TOOL = STOOL2(FP4), $BASE = SBASE(FP4.BASE_NO), $IPO_MODE = SIPO_MODE(FP4.IPO_FRAME), $LOAD = SLOAD(FP4.TOOL_NO), $ACC_AXIS[1] = SACC_JOINT(PPDAT4), $APO = SAPO_PTP(PPDAT4), $GEAR_JERK[1] = SGEAR_JERK(PPDAT4), $COLLMON_TOL_PRO[1] = USE_CM_PRO_VALUES(0) C_Spl
    
    ;ENDFOLD
    
    
    
       ENDLOOP 
    
       
    
    END
    Display More

    ISR for Slowing down the robot.

    Code: ISR_SlowSpeedTestTrue.src
    &ACCESS RV1
    DEF ISR_SlowSpeedTestTrue()
    DECL INT count
    INTERRUPT OFF 30
    
    ; Ramp down
    ;FOR count = 100 TO 0 STEP 10
    ;$OV_PRO = count 
    ;WAIT SEC 0.1
    ;ENDFOR
    
    ;Somehow the for loop did not work, but I will figure this out later... Perhaps because I cant declare INT in an interrupt?
    
    $OV_PRO = 90 
    WAIT SEC 0.1
    
    $OV_PRO = 80 
    WAIT SEC 0.1
    
    $OV_PRO = 70 
    WAIT SEC 0.1
    
    $OV_PRO = 60 
    WAIT SEC 0.1
    
    $OV_PRO = 50 
    WAIT SEC 0.1
    
    $OV_PRO = 40 
    WAIT SEC 0.1
    
    $OV_PRO = 30 
    WAIT SEC 0.1
    
    $OV_PRO = 20 
    WAIT SEC 0.1
    
    $OV_PRO = 10
    WAIT SEC 0.1
    
    $OV_PRO = 0
    WAIT SEC 0.1
    
    END
    Display More


    ISR for speeding up the robot again...

    Code: ISR_SlowSpeedTestFalse.src
    &ACCESS RV1
    DEF ISR_SlowSpeedTestFalse()
    
    DECL INT count
    
    INTERRUPT OFF 31
    
    
    
    ; Ramp up
    
    ;FOR count = 0 TO 100 STEP 10
    
    ;$OV_PRO = count 
    
    ;WAIT SEC 0.1
    
    ;ENDFOR
    
    $OV_PRO = 10 
    WAIT SEC 0.1
    $OV_PRO = 20 
    WAIT SEC 0.1
    $OV_PRO = 30 
    WAIT SEC 0.1
    $OV_PRO = 40 
    WAIT SEC 0.1
    $OV_PRO = 50 
    WAIT SEC 0.1
    $OV_PRO = 60 
    WAIT SEC 0.1
    $OV_PRO = 70 
    WAIT SEC 0.1
    $OV_PRO = 80 
    WAIT SEC 0.1
    $OV_PRO = 90 
    WAIT SEC 0.1
    $OV_PRO = 100 
    WAIT SEC 0.1
    END
    Display More


    I was looking into the manual and was thinking, that I should be able to override the acceleration, and I was trying to set

    $ACC, $ACC_OV etc, but it complained when I e.g. set

    $ACC.CP = 1.

    So therefore I went back to the OV_PRO version, and "manually" ramping down using decrementing the value with an wait statement. I think this is a bit ugly, so what is the best practice to do this?

    Thanks in advance...

    My current system contains the following information:

    • Robot: KUKA KR50 R2100
    • Controller: KR C5 dualcabinet
    • KSS 8.7.2 HF3
    • HMI version: 8.7 B394
    • Kernel system version: KS V8.7.53394
    • WorkVisual V6.0.24_Build1632
  • DS186
    Reactions Received
    200
    Trophies
    6
    Posts
    1,075
    • May 12, 2022 at 10:11 PM
    • #2

    I would either use an interrupt with a Brake command or the functions ROB_STOP() and ROB_STOP_RELEASE(). Check the manual for details and examples.

  • panic mode
    Reactions Received
    1,295
    Trophies
    11
    Posts
    13,130
    • May 12, 2022 at 10:33 PM
    • #3

    when counting down step need to be negative. so change 10 to -10 for the step value and it should be ok.

    still... i would not place loop and delays inside an interrupt. this is is better done in submit.

    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

  • SkyeFire
    Reactions Received
    1,060
    Trophies
    12
    Posts
    9,456
    • May 13, 2022 at 2:22 PM
    • #4

    I agree with Panic. Generally, you want to get in and out of an ISR as quickly as possible, except in situations where you're actually stopping the robot process (IR_STOPM comes to mind). Ramping $OV_PRO in the SPS is probably the better way to go, here.

    Alternatively, using BRAKE or ROB_STOP in your ISR should achieve the same result, unless you really want a slow ramp-down.

  • hermann
    Reactions Received
    411
    Trophies
    9
    Posts
    2,621
    • May 13, 2022 at 7:38 PM
    • #5

    One more possibility is to create a second interrupt triggered by a timer flag. In the existing interrupt set the timer to -100, this should trigger the second, in that interrupt set the override and reset the timer again.

  • panic mode
    Reactions Received
    1,295
    Trophies
    11
    Posts
    13,130
    • May 13, 2022 at 7:54 PM
    • #6

    i was reluctant to suggest that after seeing what has found its way into ISR :grinning_face_with_smiling_eyes:

    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

  • ChristianLiinHansen
    Reactions Received
    3
    Trophies
    2
    Posts
    37
    • May 13, 2022 at 10:18 PM
    • #7
    Quote from SkyeFire

    I agree with Panic. Generally, you want to get in and out of an ISR as quickly as possible, except in situations where you're actually stopping the robot process (IR_STOPM comes to mind). Ramping $OV_PRO in the SPS is probably the better way to go, here.

    Alternatively, using BRAKE or ROB_STOP in your ISR should achieve the same result, unless you really want a slow ramp-down.

    Hi SkyeFire .

    So the tool of the robot will carry a relative large load, so yes I really want a slow ramp-down of minimum 3 sec or something. Not stop immediately. but spend minimum like 3-5 sec to ramp slowly down...

    My current system contains the following information:

    • Robot: KUKA KR50 R2100
    • Controller: KR C5 dualcabinet
    • KSS 8.7.2 HF3
    • HMI version: 8.7 B394
    • Kernel system version: KS V8.7.53394
    • WorkVisual V6.0.24_Build1632
  • SkyeFire
    Reactions Received
    1,060
    Trophies
    12
    Posts
    9,456
    • May 16, 2022 at 2:12 PM
    • #8

    3-5sec decel is meters of motion, unless your robot is moving very slowly, in which case you hardly need such a long decel ramp. How did you come up with that number? I honestly can't see any application that would need such a long decel ramp, aside perhaps from carrying an open-topped bucket of water and not wanting to spill a drop.

    As long as the robot has good $LOAD data, issuing a basic BRAKE command in the ISR should give you a path-maintaining stop that's not very violent, but requires much less time that 3-5sec. Have you tried that approach?

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