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. Stäubli & Bosch 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

Robot arm stops unexpectedly when attempting to real-time control it

  • aknezevi.proton
  • April 24, 2023 at 11:40 AM
  • Thread is Resolved
  • aknezevi.proton
    Reactions Received
    5
    Trophies
    1
    Posts
    73
    • April 24, 2023 at 11:40 AM
    • #1

    Hi all!

    I am using a CS8C robot controller controlling a TX60 robot arm.

    I have a Siemens S7-300 Profibus master PLC communicating with the CS8C which is Profibus slave.

    I am attempting to simulate the alter() option on the controller using the PLC. In other words, I am attempting to use PLC as a quasi-controller for the real-time robot path control.

    To do this I have 2 tasks, communication() and movement().

    The communication() task simply collects the profibus data, and so its code is as follows:

    Code
    begin
    while(true)
    ...
    Pos.trsf.x = aioGet(IO:BLOCKA_IF10)
    Pos.trsf.y = aioGet(IO:BLOCKA_IF11)
    Pos.trsf.z = aioGet(IO:BLOCKA_IF12)
    ...
    endWhile
    end

    The movement() task is simply robot movement to Pos:

    Code
    begin
    while(true)
    movej(Pos, tTool, mNomSpeed)
    endWhile
    end

    The tasks are run with priorities N and 3 respectively, where N is the number of lines of Val3 code (including the while(true) and endWhile) in the communication() program.

    Unsurprisingly the robot motion in the beginning is a little jerky, before all the calculations are made. But then it appears to move real-time controlled. Upon touching the robot arm the feel is not at all smooth as it would be if proper movement was used, the controller-controlled one instead of the PLC-controlled one, but that is also unsurprising.

    What is surprising, however, is that robot stops after some time. According to the isEmpty() there are still movement commands present in the controller, and checking the movement data it is still changing, but the robot is stationary. There are no errors or messages on the pendant or in the log and no task is suspended. The robot simply stops.

    I am at a loss as to what is going on.

    Thank you all for taking your time to read this.

  • Go to Best Answer
  • aknezevi.proton
    Reactions Received
    5
    Trophies
    1
    Posts
    73
    • April 25, 2023 at 11:22 AM
    • #2

    In an attempt to solve the issue I have put in my code resetMotion() command inside the communication:

    Code
    begin
    ...
    if(isSettled())
    dioSet(io:BLOCKA_QX0, 1)
    else
    dioSet(io:BLOCKA_QX0, 0)
    endIf
    if(isEmpty())
    dioSet(io:BLOCKA_QX1, 1)
    else
    dioSet(io:BLOCKA_QX1, 0)
    endIf
    ...
    motionReset = dioGet(io:BLOCKA_IX0)
    if(motionReset==1)
    resetMotion()
    endIf
    ...
    end
    Display More

    With the PLC code being (written here in pseudocode):

    Code
    if BLOCKA_QX0 && !(BLOCKA_IX0) for more than N ms {
    BLOCKA_IX0 = true}
    if BLOCKA_QX1 {
    BLOCKA_IX0 = false}

    In essence, what the code does is that if the robot stops for more than a set amount of time in ms resetMotion() function is triggered until the movement command buffer is empty. In practice N was set to 10-20.

    This made robot not stop for more than some amount of ms, longer than N which was set because of the amount of time needed to clear the buffer. But the result was incredibly stuttery motion, as if the motion was viewed under a stroboscopic light. The motion is continuous and fast, then robot stops for just a few ms (the resetMotion does not trigger) but it is visible because of robot braking, then motion is resumed again continuous until another braking point.

    I will do further analysis, but this behaviour eludes explanations. Any of you know what could be going wrong?

  • Galet
    Reactions Received
    19
    Trophies
    2
    Posts
    141
    • April 25, 2023 at 6:42 PM
    • Best Answer
    • #3

    On CS8/CS9, you have a special task to manage the robot movment.

    In your Movement() program you repeat all the time a new movment even if you don't change the value !

    In this case, the robot execute same position as if it weren't moving.

    1- You can control that the position is changing before to send a new position

    2- It's bad to have a loop (even if you configure the task with low priority) without delay()

    Try

    Code
    begin
      pPosAct=here(tTool,world)
      // or : pPosAct=Pos
      while true
        // Control the distance
        if distance(pPosAct,Pos)>0.02
          pPosAct=Pos
          movej(pPosAct,tTool,mNomSpeed)
        endIf
       delay(0)
      endWhile
    end
    Display More

    Be carefull, because you don't control the PLC transmission ! If the receive wrong value, the robot can become dangerous !

    Other solution : To use Alter function...but you need option on the controller.

    Have a good day !

  • aknezevi.proton
    Reactions Received
    5
    Trophies
    1
    Posts
    73
    • April 26, 2023 at 1:52 PM
    • #4

    Hi Galet, thank you for your answer.

    Unfortunately it is not that the robot executes same position instruction over and over again. In fact, the task is running, in fact the position Pos is changing in the memory of the robot, I have confirmed that. In fact, it is changing because of the open communication link.

    One more thing, when I set blend to off (previously it was equal to joint with reach and leave both being 0.1) the robot is extremely slow in the beginning, I can see the stopping on every single individual point that was sent to it, the motion is jagged. After a while it returns to the old fast-for-a-while-but-stuttery motion.

    In my attempt to further solve the issue I was annoyed by the fact that the feel of the motion is not nice. I wanted a pretty motion, so I changed movej, which is optimized movement and so it is not necessarily smooth in space, with the movel command, the linear movement in space.

    The change from movej to movel inside movement() task solved all my problems. The robot no longer stops randomly and the motion is not stuttery, it is smooth. How exactly this change solves my problems I have no idea.

    It might have something to do with the fact that I was giving point position in joint movement command, but that would mean bad coding on the side of Staubli themselves. It might be blending problem, because blending is designed to be in space, but that would also be bad coding from Staubli side.

  • Galet
    Reactions Received
    19
    Trophies
    2
    Posts
    141
    • April 27, 2023 at 6:14 PM
    • #5

    Hi,

    Can you try with synchronous task ?

    Have you try with Alter function ?

    Best regards...

  • aknezevi.proton
    Reactions Received
    5
    Trophies
    1
    Posts
    73
    • April 28, 2023 at 7:58 AM
    • #6

    Hi Galet, I have tried with the synchronous task with 4ms and 8ms to no avail.

    I have not tried alter function because that is exactly what I want to simulate, the whole point is not to use alter function.

  • Galet
    Reactions Received
    19
    Trophies
    2
    Posts
    141
    • April 28, 2023 at 8:10 AM
    • #7

    Hello,

    Ok. If I have time, i'll make a small test with your program. What's the speed of the data variation from the PLC ?

    What's the reason you don't want to use Alter ?

    Do you know that you can activate, for test, all option in Demo Mode ?

    Best regards

  • Galet
    Reactions Received
    19
    Trophies
    2
    Posts
    141
    • May 1, 2023 at 5:37 PM
    • #8

    Hello,

    I try this program :

    The Start()

    Code
    begin
      resetMotion(jInit)
      waitEndMove()
      
      // Waiting Init AI
      pPos = here(tTool,world)
      wait(abs(aioGet(aiValX)-pPos.trsf.x)<nStep and abs(aioGet(aiValY)-pPos.trsf.y)<nStep and abs(aioGet(aiValZ)-pPos.trsf.z)<nStep)
      
      taskCreate "Mvt",100,tskMvt()
      wait(taskStatus("Mvt")==1)
      
      do
        setMutex(bMutex)
        pPos.trsf.x=aioGet(aiValX)
        pPos.trsf.y=aioGet(aiValY)
        pPos.trsf.z=aioGet(aiValZ)
        bMutex=false
        
        delay(0)
      until false
    end
    Display More

    And the tskMvt()

    Code
    begin
      pAct=here(tTool,world)
      while(true)
        if distance(pAct.trsf,pPos.trsf)>nStep
          setMutex(bMutex)
          movej(pPos, tTool, mNomSpeed)
          bMutex=false
          pAct=pPos
        endIf
        
        delay(0)
      endWhile
    end
    Display More

    nStep Value is 0.5 mm

    mNomSpeed.blend is Joint

    mNomSpeed.leave=mNomSpeed.reach are 0.1mm

    On simulator (SRC 7.11.2) the mouvement is correct.

    The problem is, in this concept, to change directly the value. If I add 100 mm to X and, during the mouvement, I add 100 to Z, the variation are not simultaneous.

    I think the best is to define X+, X-, Y+, Y-, Z+ and Z- buttons (Digital Inputs), to change, step by step the value.

    Have a good day,

  • aknezevi.proton
    Reactions Received
    5
    Trophies
    1
    Posts
    73
    • May 2, 2023 at 8:29 AM
    • #9

    Hello Galet, thanks again,

    Yes, I do know that I can activate demo licenses for almost all options on CS8C.

    The reason I do not want to do this, as mentioned above, is that I am doing an alter simulation, that is I want to make a program such that it modifies position sent to robot, this is only the beginning and a necessary step in the process, because if I cannot real-time control robot using the PLC the task is doomed.

    The data variation is roughly 2mm/4ms, that is, the sent position of the robot changes roughly by 2mm during 4ms (1 cycle time), but I varied from 0.4 to 4 mm per 4ms.

    Thank you for running the simulation, but I need such precision so that 0.5mm of nStep is at the very boundary of barely usable, the precision of the robot that I would need is 0.2mm at max, so I aim at 0.1mm.

    Also, yes, the not simultaneous variations is expected, but that is why, in program, I use a vector of changing direction, not individual axes.

    I might give it a try making sure that position is changing, I do have slight problem with being forced into using movel (because of singularities). But I have other operations that need testing first.

    However, none of this explains why the robot would stop if using movej and never when using movel (and in movel is also faster, more continuous and has nicel motion).

  • Galet
    Reactions Received
    19
    Trophies
    2
    Posts
    141
    • May 2, 2023 at 7:09 PM
    • #10

    Ok.

    Are you sure that the speed of Profibus is anough to control the position "In real Time" ?

    Is your robot "Absolut" to respect a precision like 0.1 mm ?

    I understand that, for you, this test is first Step...

    You can reduce the nStep Value to 0.2 mm but it's not logic to have 0.1 mm in the blending function.

    In my test, i use moveJ and no problem in the movement. I think the difference is in the approximation calcul between Joint or Linear mouvement.

    Singularities : 500 mm/s is a problem for singularities positions !

    The Alter function don't move the robot to a absolut position but modifie the position with an offset or vector.

    What the position of Stäubli Services about your (medical ?) question ?

    Best regards

  • aknezevi.proton
    Reactions Received
    5
    Trophies
    1
    Posts
    73
    • May 3, 2023 at 8:06 AM
    • #11

    Hi Galet,

    I do not know the exact speed of profibus, but for a fact I know that data transmission is < 10ms (both-ways speed) because earlier I monitored some things like arm position and joint forces over profibus. That should be enough, but even if it is not, if it was 100ms speed the robot should not stop.

    The arm has precision of 0.02mm, so 0.1mm it should have, it is a whole order of magnitude larger.

    If I understood correctly your test was a simulation in SRS, and was not downloaded to actual robot controller? From my experiences with other simulation software, like KUKA and Motoman the simulation is not complete and the robot controller behaves differently during edge cases than simulation would suggest.

    Quote


    I think the difference is in the approximation calcul between Joint or Linear mouvement.

    Singularities : 500 mm/s is a problem for singularities positions !

    That is interesting, thank you. The singularities are not problem for movej, and yet it is movej which fails, not movel.

    Quote


    The Alter function don't move the robot to a absolut position but modifie the position with an offset or vector.

    Precisely the strength of alter function as opposed to any simulation. It is quite impossible to use third-party controller to make the CS8C alter the position real-time, as opposed to simply adding a new position.

    Quote


    What the position of Stäubli Services about your (medical ?) question ?

    I have not yet got a response from Staubli regarding this question, which is why I posted here.

  • Galet
    Reactions Received
    19
    Trophies
    2
    Posts
    141
    • May 4, 2023 at 8:24 AM
    • #12

    Hi,

    Quote


    The arm has precision of 0.02mm, so 0.1mm it should have, it is a whole order of magnitude larger.

    The repetability is 0.02 for this arm ... but not the precision !

    Quote

    If I understood correctly your test was a simulation in SRS, and was not downloaded to actual robot controller? From my experiences with other simulation software, like KUKA and Motoman the simulation is not complete and the robot controller behaves differently during edge cases than simulation would suggest.

    On SRS, if you load the good Emulator and use correct Payload, the simulation is the same as the real robot. I use SRS because I don't have always the robot...aned the PLC with Profibus.

    Quote

    Precisely the strength of alter function as opposed to any simulation. It is quite impossible to use third-party controller to make the CS8C alter the position real-time, as opposed to simply adding a new position.

    I don't anderstand...

    Have a nice day...

  • aknezevi.proton
    Reactions Received
    5
    Trophies
    1
    Posts
    73
    • May 5, 2023 at 3:00 PM
    • #13

    Thank you, Galet.

    I ran the program with the following code:

    Code
    posDist = distance(Pos, Pos_LC)
    if posDist > posDistTrig then
    movej(Pos, tTool, mNomSpeed)
    endIf
    Pos_LC = Pos

    In essence this code makes sure that only such movements are calculated which are sufficiently different from each other. I have set posDistTrig to 0.1mm.

    Still, if I use movej the robot stops unexpectedly.

    It did, however, increase the responsivity of robot by a noticeable amount. I still have to use movel to make the robot not stop randomly.

    Quote


    The repetability is 0.02 for this arm ... but not the precision !

    I understand the difference, but the robot precision cannot be far off repeatability. I am unable to find the precision for TX60 arm, would you have it? Not a single data sheet I have available has that info, only repeatability.

    Quote


    On SRS, if you load the good Emulator and use correct Payload, the simulation is the same as the real robot. I use SRS because I don't have always the robot...aned the PLC with Profibus.

    The simulation is only ever a simulation. The physical robot controller and arm are the ultimate authority on what is possible. In my example, no matter what I do, if I use movej in this way the robot unexpectedly and randomly stops. Movel functions fine. So there is a fundamental problem here.

  • Galet
    Reactions Received
    19
    Trophies
    2
    Posts
    141
    • May 5, 2023 at 5:00 PM
    • #14
    Code
    posDist = distance(Pos, Pos_LC)
    if posDist > posDistTrig then
      movej(Pos, tTool, mNomSpeed)
      Pos_LC = Pos
    endIf

    is best if you want to memorize the distance between the last mouvement and your actual coomand. You need to initialize Pos_LC.

    The robot's factories give, for industrial robots, only repetability (ABB/KUKA/Fanuc/Stäubli...) If you need realy precision, you need to ajust the kinematic to the real arm...and you win an Absolut robot.

    Ok, the simulation is only a simulation, to control the real position, you need the real arm. But to solve the guidance, I think the simulation give you the same result.

    Fundamental problem : Ask to Stäubli technical service.

    My opinion is that, for your test, it's not possible to have the same value in the blending and in the posDistTrig. Can you try with posDistTrig=0.3 mm ?

    For you application, you need a relative movement or an absolut position ?

    Best regards,

  • aknezevi.proton
    Reactions Received
    5
    Trophies
    1
    Posts
    73
    • May 8, 2023 at 8:11 AM
    • #15

    Thank you Galet.

    Quote


    My opinion is that, for your test, it's not possible to have the same value in the blending and in the posDistTrig. Can you try with posDistTrig=0.3 mm ?

    For my test here it does not matter, the position changes in steps of 3.1 mm on the PLC (the encoder has few impulses), so that fundamentally cannot be the problem here. This code only ensures that the movement is calculated if and only if the position changes, but the change is fundamentally always way more than blending distance.

    Quote


    For you application, you need a relative movement or an absolut position ?

    I need to track the position of an object to a certain precision, at least 0.5mm precision, so I would like to have a leaway so my goal is 0.1mm.

  • Galet
    Reactions Received
    19
    Trophies
    2
    Posts
    141
    • May 10, 2023 at 12:52 PM
    • #16

    Hello Ak,

    I don't know why my result seems correct and not yours...

    Quote

    the encoder has few impulses

    Have you lookeed from the side of Tracking function ? The mobile frame can be a good solution...

  • aknezevi.proton
    Reactions Received
    5
    Trophies
    1
    Posts
    73
    • May 10, 2023 at 1:31 PM
    • #17

    Hi Galet,

    Quote

    Have you lookeed from the side of Tracking function ? The mobile frame can be a good solution...

    We want to simulate tracking, not use already existing controller option.

    In the meantime the Staubli have reached back and said that "simulation works only for higher controller, 7.6 and onward". I am working with s6.8. I am not fully sure what that means.

  • Galet
    Reactions Received
    19
    Trophies
    2
    Posts
    141
    • May 10, 2023 at 6:28 PM
    • #18

    Hello AK,

    There are many differences between SRC6 and SRC7. I don't know if some concern your test...but it's very important information (my test was with SRC 7).

    I don't anderstand why you try to have Alter functionalities without the option... or Traking functionnalities without the option... Probably your application is little bit confidential (:))

    I think that the best next step for you is to contact directly Stäubli services (Between 6.8 and 7,probably an Upgrade of your controller is possible...perhaps to 7.6 )

    Have a good day,

  • aknezevi.proton
    Reactions Received
    5
    Trophies
    1
    Posts
    73
    • May 11, 2023 at 7:48 AM
    • #19

    Thank you for your time, it has been most helpful.

    Have a good day!

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

  • Real-time path correction
  • tx60
  • CS8C
  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