Inconsistent frame timings?

I’m hoping to use the robot GPIO to send timing-sensitive triggers to my measurement equipment, but when I look at the output waveform it looks like the time between frames is not always 2ms - sometimes there are 3ms and sometimes 1ms between output changes. I’m running a very simple URscript to just toggle the output high and low while I check it on an oscilloscope:

def toggle():
  trigger_pin = 7
  while True:
    set_standard_digital_out(trigger_pin, True)
    sync()
    set_standard_digital_out(trigger_pin, False)
    sync()
  end
end

Here’s 50ms of the waveform:

This plot has 5ms per horizontal division. You can see that the times between edges are not always 2ms. Can anyone help me understand what is happening here?

Why don’t you try to use sleep() instead? From URScript manual:

It should be noted that even though the sleep instruction does not control the robot,
it still uses “physical” time. The same is true for the sync instruction. Inserting sync or
sleep will allow time for other threads to be executed and is therefore recommended
to use next to computational heavy instructions or inside infinite loops that do not control
the robot, otherwise an exception like “Runtime is too much behind” can be raised
with a consequent protective stop.

So apparently the function sync() does not mean it will run on an exact amount of time, but sleep does. So you can make a parallel thread that only runs toggle()

Controller with a program running is allowed to be up to 2 cycles behind in communication with hardware. So you can observe a jitter of couple ms when program is running and robot is moving. In extreme cases 2ms pulse might not be generated at all.
When robot is stationary the jitter is allowed to be even higher.
To take it into account pulses should be longer than 8ms.

Could you write little more about the use case. Is it needed to have edge in a precise time? Is delay between pulses that need to be precise? Is duration of the pulse important?

Hi @cgs , thanks for the suggestion. I tried swapping the sync() lines out for sleep(0.002), but the result was exactly the same. It seems like there’s a separate 1kHz clock that operates the I/O, and it depends on when the main control logic actually sets its output as to which of the 1kHz clock edges catches the change.

Hi @mmi , thank you for that information. Is there any documentation floating around that outlines these restrictions?

The use case is triggering a laser for making measurements while the robot is moving; also for synchronising the motion of two robots while taking measurements. The laser is sensitive to the period between triggers, so having a range of 1ms - 3ms is far too wide. Similarly, even ignoring the trigger period, having some triggers delayed by 1ms means the sample location would be out by a quarter of the expected distance between measurements.

I can use an external system with reliable triggering frequency, but then would want to know the robot pose for each sample. Do you know if the RTDE measurements are similarly variable in their temporal distribution, or are they more reliable?

This is not specified parameter, but your observation is completely true - 500Hz real time loop is competing with 1kHz thread on a communication level.
Synchronization between them depends on a RT cycle processing time that is by coincidence close to 1ms. RT thread is allowed to exceed 2ms by small margin for small amount of time.

If it’s an option then signal generated by robot should be divided by 2 with external counter - that would give stable 125Hz signal for great majority of time.

Another option worth trying is to add load to RT thread, so it always executes longer than 1ms. Single, or 2 calls to inv kinematics should be enough. RT execution time can be observed over RTDE interface (actual_execution_time).

Encoder inputs (look into coveyor tracking chapter in manuals) could be used to validate if no cycle was missed.

RTDE communication thread runs with lower priority than RT threads, so jitter would not be smaller.

Hi @mmi , that’s really helpful. I’ll have a good look at the execution time and how it relates to the jitter.

In the mean time, can you please clarify about RTDE: I don’t think the exact timing of the messages is important to me as much as the timing the actual measurements. Are the measurements (actual_TCP_pose, actual_q, etc) reliably made every 2ms, or can they experience significant jitter too?

Also, are the 500Hz RT loop and 1kHz I/O loop consistently aligned, or can their relative timing be different every time the robot starts? I ask because if their alignment is not consistent, then I wouldn’t be able to suppress the jitter by applying load because that load could fix the problem one day, but exacerbate it the next day.

RTDE runs with priority just slightly lower than RT thread so I’d say that it should be reliable.

500Hz RT loop is synchronized from 1kHz thread.