-
Notifications
You must be signed in to change notification settings - Fork 393
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Time execution of robot_wrapper.display are dependent on the call frequency ? #1068
Comments
Using |
Many thanks @jmirabel this solved my timing issues. from multiprocessing import Process, Lock
from multiprocessing.sharedctypes import Value, Array
from ctypes import c_double
import pinocchio as pin
import numpy as np
import time
class NonBlockingViewer():
def __init__(self,robot,timeIntervals=0.05):
# a shared c_double array
self.timeIntervals = timeIntervals
self.shared_q_viewer = Array(c_double, robot.nq, lock=False)
p = Process(target=self.display_process, args=(robot, self.shared_q_viewer))
p.start()
def display_process(self,robot, shared_q_viewer):
''' This will run on a different process'''
q_viewer = robot.q0.copy()
while(1):
for i in range(robot.nq):
q_viewer[i] = shared_q_viewer[i]
robot.display(q_viewer)
time.sleep(self.timeIntervals)
def display(self,q):
for i in range(len(self.shared_q_viewer)):
self.shared_q_viewer[i] = q[i]
def benchmark():
pin.switchToNumpyMatrix()
modelPath = "/opt/openrobots/lib/python3.5/site-packages/../../../share/example-robot-data/robots"
urdf = modelPath + "/solo_description/robots/solo.urdf"
robot = pin.RobotWrapper.BuildFromURDF( urdf, modelPath, pin.JointModelFreeFlyer())
robot.initDisplay(loadModel=True)
def job(n,t,disp):
for i in range(n):
disp(robot.q0)
robot.q0[7:]+=0.01
time.sleep(t)
#blocking, in sync
t=time.time()
job(10000,0.01,robot.display)
print (time.time()-t)
#blocking, not synchronous
robot.viewer.gui.setRefreshIsSynchronous(False)
t=time.time()
job(10000,0.01,robot.display)
print (time.time()-t)
#non blocking
nbv = NonBlockingViewer(robot,0.0)
t=time.time()
job(10000,0.01,nbv.display)
print (time.time()-t)
benchmark() benchmarks give for 10k calls delayed by 10ms: So basically, the shared memory only saves 0.5ms per display calls. |
A few remarks:
Putting the two together, I think the 1.55 extra seconds (in 101.55s) are due, almost entirely, to the bad accuracy of |
You are right, the shared memory method is basically the reference point (Comparable of doing nothing), this should not really be part of the benchmark. |
Why to not set this value by default in gepetto-gui? |
I asked myself the same thing. I think the only reason was for code like:
When not synchronous, you don't know which image will be rendered to the file. However, after thinking twice about it and checking the source code, I think you are still guaranteed to render to latest one. I will change the default for some time on my laptop to see if I encounter any other issues. |
Thanks @jmirabel for solving this issue. |
To give a little bit of context, I'm planning on making the connection with the viewer non blocking by using a shared memory and the multiprocess module. While doing so, I realized some strange behavior, that someone might be able to explain :
I ran some test and realized that execution time of python calls to robot_wrapper.display are dependent on the call frequency.
If called a few times, display execution time is about 1ms in the worst case on my machine,
however, called in a loop, with a reasonable delay of 50ms between calls increase this time to 17ms!
cProfile.run('d(1,0.05)')
gives
but
cProfile.run('d(1000,0.05)')
givesEven more bizarre, when I call
d(100,0.)
, the cpu spend 0.28ms per display calls in average..but
d(1000,0.)
gives an average of 3 to 6ms per display calls.The text was updated successfully, but these errors were encountered: