Skip to content
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

Investigate on how to reduce the CPU usage when a new dataset is loaded #24

Open
GiulioRomualdi opened this issue Jan 25, 2022 · 12 comments

Comments

@GiulioRomualdi
Copy link
Member

In the past few days, I noticed that the application is greedy for resources. This happens when a new dataset is loaded. Indeed on the icub-console-gui the CPU usage jumps to 160% when the dataset is loaded. I tried to investigate the problem and I noticed that the thread related to meshcat requires more than its period (0.02s) to compute a cycle.

def run(self):
base_rotation = np.eye(3)
base_position = np.array([0.0, 0.0, 0.0])
while True:
start = time.time()
if self.state == PeriodicThreadState.running:
# These are the robot measured joint positions in radians
joints = self._signal_provider.data['robot_logger_device']['joints_state']['positions']['data']
self._meshcat_visualizer.set_multy_body_system_state(base_position, base_rotation,
joint_value=joints[self._signal_provider.index, :],
model_name="robot")
if self.state == PeriodicThreadState.closed:
return
sleep_time = self._period - (time.time() - start)
if sleep_time > 0:
time.sleep(sleep_time)

In the beginning, I thought that the problem was related to the dynamical allocation of the vector associated with the robot joints and the base pose every time set_multy_body_system_state is called.

base_rotation_idyn = idyn.Rotation()
base_position_idyn = idyn.Position()
base_pose_idyn = idyn.Transform()
for i in range(0, 3):
base_position_idyn.setVal(i, base_position[i])
for j in range(0, 3):
base_rotation_idyn.setVal(i, j, base_rotation[i, j])
base_pose_idyn.setRotation(base_rotation_idyn)
base_pose_idyn.setPosition(base_position_idyn)
if len(joint_value) != self.model[model_name].getNrOfJoints():
msg = "The size of the joint_values is different from the model DoFs"
warnings.warn(msg, category=UserWarning, stacklevel=2)
return
joint_pos_idyn = idyn.VectorDynSize(self.model[model_name].getNrOfJoints())
for i in range(0, self.model[model_name].getNrOfJoints()):
joint_pos_idyn.setVal(i, joint_value[i])

I reduced the time this memory allocation is performed (associated PR: robotology/idyntree#959) but the problem was still there.

To better understand the problem I wrote a simple script that isolates the "slow" function (set_multy_body_system_state) (I know there is a typo. I'm sorry for that 😞)

import numpy as np
import os
import cProfile
import io
import pstats

from robot_visualizer.meshcat_visualizer import MeshcatVisualizer


def get_model_path(robot_name='iCubGazeboV3'):
    seperbuild_prefix = os.environ["ROBOTOLOGY_SUPERBUILD_INSTALL_PREFIX"]
    robots_folder = os.path.join("share", "iCub", "robots", robot_name)

    return os.path.join(seperbuild_prefix, robots_folder, "model.urdf")


def get_joint_list():
    joint_list = ['neck_pitch', 'neck_roll', 'neck_yaw',
                  'torso_pitch', 'torso_roll', 'torso_yaw',
                  'l_shoulder_pitch', 'l_shoulder_roll', 'l_shoulder_yaw', 'l_elbow',
                  'r_shoulder_pitch', 'r_shoulder_roll', 'r_shoulder_yaw', 'r_elbow',
                  'l_hip_pitch', 'l_hip_roll', 'l_hip_yaw', 'l_knee', 'l_ankle_pitch', 'l_ankle_roll',
                  'r_hip_pitch', 'r_hip_roll', 'r_hip_yaw', 'r_knee', 'r_ankle_pitch', 'r_ankle_roll']

    return joint_list


def profile(func):
    def wrapper(*args, **kwargs):
        pr = cProfile.Profile()
        pr.enable()
        retval = func(*args, **kwargs)
        pr.disable()
        s = io.StringIO()
        sortby = pstats.SortKey.CUMULATIVE  # 'cumulative'
        ps = pstats.Stats(pr, stream=s).sort_stats(sortby)
        ps.print_stats()
        print(s.getvalue())
        return retval

    return wrapper


@profile
def foo(vis, pos, rot, joints):
    vis.set_multy_body_system_state(pos, rot, joints)

def main():
    vis = MeshcatVisualizer()
    vis.load_model_from_file(get_model_path(), get_joint_list(), color=[1,1,1,0.8])

    joints = [1]*len(get_joint_list())
    rot = np.eye(3)
    pos = [0,0,0]
    foo(vis, pos, rot, joints)

if __name__ == "__main__":
    main()

Accordingly to the outcome seems that the bottleneck is caused by the send function inside the meshcat package. I am afraid that we should increase the period of the meshcat thread in order to avoid undesired behavior in the application.

@traversaro @diegoferigo @isorrentino @paolo-viceconte @RiccardoGrieco @S-Dafarra do you have any idea on how to avoid this problem?

   ncalls  tottime  percall  cumtime  percall filename:lineno(function)
        1    0.000    0.000    0.017    0.017 test_profiling.py:45(foo)
        1    0.001    0.001    0.017    0.017 /home/gromualdi/robot-code/robot-log-visualizer/robot_visualizer/meshcat_visualizer.py:190(set_multy_body_system_state)
       42    0.001    0.000    0.014    0.000 /home/gromualdi/robot-code/robot-log-visualizer/robot_visualizer/meshcat_visualizer.py:110(__apply_transform)
       42    0.000    0.000    0.012    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/meshcat/visualizer.py:151(set_transform)
       42    0.008    0.000    0.012    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/meshcat/visualizer.py:56(send)
       42    0.000    0.000    0.003    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/umsgpack.py:664(_packb3)
   966/42    0.001    0.000    0.003    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/umsgpack.py:544(_pack3)
       42    0.000    0.000    0.002    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/umsgpack.py:438(_pack_map)
       42    0.000    0.000    0.002    0.000 /home/gromualdi/robot-code/robot-log-visualizer/robot_visualizer/meshcat_visualizer.py:36(__is_mesh)
       42    0.000    0.000    0.001    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/umsgpack.py:423(_pack_array)
       42    0.000    0.000    0.001    0.000 /home/gromualdi/robot-code/robotology-superbuild/build/install/lib/python3/dist-packages/idyntree/swig.py:4176(getFileLocationOnLocalFileSystem)
       42    0.001    0.000    0.001    0.000 {built-in method idyntree._iDynTree.ExternalMesh_getFileLocationOnLocalFileSystem}
       42    0.000    0.000    0.001    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/zmq/sugar/socket.py:549(send_multipart)
      672    0.000    0.000    0.001    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/umsgpack.py:325(_pack_float)
       84    0.000    0.000    0.001    0.000 {built-in method numpy.core._multiarray_umath.implement_array_function}
      126    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/zmq/sugar/socket.py:480(send)
       42    0.000    0.000    0.000    0.000 <__array_function__ internals>:177(diag)
      210    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/umsgpack.py:336(_pack_string)
       42    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/meshcat/commands.py:40(lower)
       42    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/numpy/lib/twodim_base.py:234(diag)
       42    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/meshcat/visualizer.py:145(__getitem__)
     3570    0.000    0.000    0.000    0.000 {built-in method builtins.isinstance}
       42    0.000    0.000    0.000    0.000 <__array_function__ internals>:177(concatenate)
       69    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robotology-superbuild/build/install/lib/python3/dist-packages/idyntree/swig.py:4781(__getitem__)
       69    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.LinksSolidShapesVector___getitem__}
       42    0.000    0.000    0.000    0.000 /usr/lib/python3.8/posixpath.py:117(splitext)
       42    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robotology-superbuild/build/install/lib/python3/dist-packages/idyntree/swig.py:2960(__mul__)
       84    0.000    0.000    0.000    0.000 {method 'flatten' of 'numpy.ndarray' objects}
      126    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robotology-superbuild/build/install/lib/python3/dist-packages/idyntree/swig.py:4081(asExternalMesh)
       42    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.Transform___mul__}
       42    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/meshcat/path.py:7(append)
      966    0.000    0.000    0.000    0.000 {built-in method _struct.pack}
      966    0.000    0.000    0.000    0.000 {method 'write' of '_io.BytesIO' objects}
     1638    0.000    0.000    0.000    0.000 {method 'get' of 'dict' objects}
       42    0.000    0.000    0.000    0.000 {method 'dot' of 'numpy.ndarray' objects}
       42    0.000    0.000    0.000    0.000 /usr/lib/python3.8/genericpath.py:121(_splitext)
      126    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.SolidShape_asExternalMesh}
       43    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robotology-superbuild/build/install/lib/python3/dist-packages/idyntree/swig.py:4211(getLinkSolidShapes)
       42    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/meshcat/visualizer.py:97(view_into)
       42    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robotology-superbuild/build/install/lib/python3/dist-packages/idyntree/swig.py:1133(toNumPy)
       42    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robotology-superbuild/build/install/lib/python3/dist-packages/idyntree/swig.py:2967(asHomogeneousTransform)
       42    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robotology-superbuild/build/install/lib/python3/dist-packages/idyntree/swig.py:3156(__call__)
       42    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.Matrix4x4_toNumPy}
       27    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robotology-superbuild/build/install/lib/python3/dist-packages/idyntree/swig.py:4244(getLinkName)
       42    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robotology-superbuild/build/install/lib/python3/dist-packages/idyntree/swig.py:4045(getLink_H_geometry)
      490    0.000    0.000    0.000    0.000 {built-in method builtins.len}
       42    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.Transform_asHomogeneousTransform}
       42    0.000    0.000    0.000    0.000 {built-in method numpy.array}
       42    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robotology-superbuild/build/install/lib/python3/dist-packages/idyntree/swig.py:4069(isExternalMesh)
       42    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robotology-superbuild/build/install/lib/python3/dist-packages/idyntree/swig.py:4036(getName)
       43    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.ModelSolidShapes_getLinkSolidShapes}
       42    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robotology-superbuild/build/install/lib/python3/dist-packages/idyntree/swig.py:1423(toNumPy)
       42    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robotology-superbuild/build/install/lib/python3/dist-packages/idyntree/swig.py:4182(getScale)
       42    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.LinkPositions___call__}
       42    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.SolidShape_getLink_H_geometry}
      294    0.000    0.000    0.000    0.000 {method 'encode' of 'str' objects}
       42    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/meshcat/path.py:16(lower)
       42    0.000    0.000    0.000    0.000 {built-in method numpy.zeros}
       27    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.Model_getLinkName}
       42    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.SolidShape_getName}
       42    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.Vector3_toNumPy}
       42    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.SolidShape_isExternalMesh}
       42    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.ExternalMesh_getScale}
       42    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/meshcat/visualizer.py:90(__init__)
       42    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/numpy/lib/twodim_base.py:230(_diag_dispatcher)
       84    0.000    0.000    0.000    0.000 {method 'rfind' of 'str' objects}
       42    0.000    0.000    0.000    0.000 {method 'split' of 'str' objects}
       84    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/meshcat/path.py:4(__init__)
       26    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robotology-superbuild/build/install/lib/python3/dist-packages/idyntree/swig.py:788(setVal)
        1    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robotology-superbuild/build/install/lib/python3/dist-packages/idyntree/swig.py:4858(ForwardPositionKinematics)
        1    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robotology-superbuild/build/install/lib/python3/dist-packages/idyntree/swig.py:2745(__init__)
       42    0.000    0.000    0.000    0.000 {method 'join' of 'str' objects}
        1    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.ForwardPositionKinematics}
        1    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robotology-superbuild/build/install/lib/python3/dist-packages/idyntree/swig.py:1789(__init__)
        1    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robotology-superbuild/build/install/lib/python3/dist-packages/idyntree/swig.py:2931(__init__)
       26    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.VectorDynSize_setVal}
       42    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/numpy/core/multiarray.py:148(concatenate)
       42    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/meshcat/commands.py:36(__init__)
       42    0.000    0.000    0.000    0.000 {method 'lower' of 'str' objects}
        9    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robotology-superbuild/build/install/lib/python3/dist-packages/idyntree/swig.py:1018(setVal)
       42    0.000    0.000    0.000    0.000 {built-in method posix.fspath}
       42    0.000    0.000    0.000    0.000 {built-in method numpy.asanyarray}
       42    0.000    0.000    0.000    0.000 {method 'items' of 'dict' objects}
       42    0.000    0.000    0.000    0.000 {built-in method builtins.abs}
       42    0.000    0.000    0.000    0.000 {method 'getvalue' of '_io.BytesIO' objects}
        1    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.new_Rotation}
        1    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robotology-superbuild/build/install/lib/python3/dist-packages/idyntree/swig.py:778(__init__)
        3    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robotology-superbuild/build/install/lib/python3/dist-packages/idyntree/swig.py:1373(setVal)
        1    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.new_Transform}
        1    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robotology-superbuild/build/install/lib/python3/dist-packages/idyntree/swig.py:4346(visualSolidShapes)
        1    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.Position_swiginit}
        1    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robot-log-visualizer/robot_visualizer/meshcat_visualizer.py:119(__model_exists)
        3    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robotology-superbuild/build/install/lib/python3/dist-packages/idyntree/swig.py:4259(getNrOfJoints)
        1    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.Rotation_swiginit}
        9    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.Matrix3x3_setVal}
        1    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robotology-superbuild/build/install/lib/python3/dist-packages/idyntree/swig.py:2943(setRotation)
        3    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.Vector3_setVal}
        1    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robotology-superbuild/build/install/lib/python3/dist-packages/idyntree/swig.py:2946(setPosition)
        1    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.Model_visualSolidShapes}
        1    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.new_VectorDynSize}
        1    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robotology-superbuild/build/install/lib/python3/dist-packages/idyntree/swig.py:4241(getNrOfLinks)
        3    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.Model_getNrOfJoints}
        1    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.Transform_swiginit}
        1    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.VectorDynSize_swiginit}
        1    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.Transform_setRotation}
        1    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.Transform_setPosition}
        1    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.new_Position}
        1    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.Model_getNrOfLinks}
        1    0.000    0.000    0.000    0.000 {method 'keys' of 'dict' objects}
        1    0.000    0.000    0.000    0.000 {method 'disable' of '_lsprof.Profiler' objects}
@traversaro
Copy link
Contributor

Accordingly to the outcome seems that the bottleneck is caused by the send function inside the meshcat package.

Probably an obvious question, but I am missing something: how can you understand this from the output you posted?

@GiulioRomualdi
Copy link
Member Author

Accordingly to the outcome seems that the bottleneck is caused by the send function inside the meshcat package.

Probably an obvious question, but I am missing something: how can you understand this from the output you posted?

As you can see here the cumtime is pretty high (0.012)

   ncalls  tottime  percall  cumtime  percall filename:lineno(function)
       42    0.000    0.000    0.012    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/meshcat/visualizer.py:151(set_transform)

From the documentation

tottime
for the total time spent in the given function (and excluding time made in calls to sub-functions)

[...]

cumtime
is the cumulative time spent in this and all subfunctions (from invocation till exit). This figure is accurate even for recursive functions.

@traversaro
Copy link
Contributor

Thanks, I wonder how I was not able to see it before.

@GiulioRomualdi
Copy link
Member Author

Bytheway if you noticed here #24 (comment) the cumulative time per call is actually small. So the problem happens in the case of a multibody system where meshcat should send to the server a pose for each mesh (in our case 42)

@traversaro
Copy link
Contributor

Yes, probably having some kind of set_transforms to set all the transforms at once would be useful (this was exactly the bottleneck in the MATLAB visualizer). It may be worth to check what they do in Drake.

@traversaro
Copy link
Contributor

@GiulioRomualdi
Copy link
Member Author

It may be worth to check what they do in Drake.

See https://github.com/RobotLocomotion/drake/blob/62750b830658b2013113ce26e9f9b56327e945c4/bindings/pydrake/systems/meshcat_visualizer.py#L595 .

So it's similar to what we do in our code

for link_index in range(0, self.model[model_name].getNrOfLinks()):

@diegoferigo
Copy link
Member

@GiulioRomualdi when debugging, it's often more useful ordering the function calls with tottime instead of cumtime, you can do it as follows:

python -m cProfile -s tottime mu_script.py 

This being said, I also noticed in another application that meshcat is pretty slow when sending the json message with the new link transform. Multiply this time for all the links and you can easily get the problems that have occurred here. Though, I couldn't find any way to send a single message containing multiple transforms.

@traversaro
Copy link
Contributor

However, if the problem is sending the transform to meshcat, I am not sure why this happens only when loading a dataset and not when the dataset is played back.

@GiulioRomualdi
Copy link
Member Author

GiulioRomualdi commented Jan 25, 2022

However, if the problem is sending the transform to meshcat, I am not sure why this happens only when loading a dataset and not when the dataset is played back.

Ops. I should explain it better. This happens only after loading the dataset (so also when it is played back). If the dataset is not loaded the meshcat.set_transform() is not called.

@GiulioRomualdi
Copy link
Member Author

@diegoferigo I sorted the list by tottime (and the winner is meshcat send)

 ncalls  tottime  percall  cumtime  percall filename:lineno(function)
       42    0.009    0.000    0.013    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/meshcat/visualizer.py:56(send)
       42    0.001    0.000    0.001    0.000 {built-in method idyntree._iDynTree.ExternalMesh_getFileLocationOnLocalFileSystem}
   966/42    0.001    0.000    0.003    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/umsgpack.py:544(_pack3)
       42    0.001    0.000    0.016    0.000 /home/gromualdi/robot-code/robot-log-visualizer/robot_visualizer/meshcat_visualizer.py:110(__apply_transform)
      126    0.001    0.000    0.001    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/zmq/sugar/socket.py:480(send)
        1    0.001    0.001    0.019    0.019 /home/gromualdi/robot-code/robot-log-visualizer/robot_visualizer/meshcat_visualizer.py:192(set_multy_body_system_state)
      672    0.000    0.000    0.001    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/umsgpack.py:325(_pack_float)
     3570    0.000    0.000    0.000    0.000 {built-in method builtins.isinstance}
       84    0.000    0.000    0.001    0.000 {built-in method numpy.core._multiarray_umath.implement_array_function}
       42    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/numpy/lib/twodim_base.py:234(diag)
      210    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/umsgpack.py:336(_pack_string)
       42    0.000    0.000    0.002    0.000 /home/gromualdi/robot-code/robot-log-visualizer/robot_visualizer/meshcat_visualizer.py:36(__is_mesh)
       42    0.000    0.000    0.000    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/meshcat/commands.py:40(lower)
       42    0.000    0.000    0.003    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/umsgpack.py:438(_pack_map)
       42    0.000    0.000    0.002    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/umsgpack.py:423(_pack_array)
       84    0.000    0.000    0.000    0.000 {method 'flatten' of 'numpy.ndarray' objects}
       69    0.000    0.000    0.000    0.000 {built-in method idyntree._iDynTree.LinksSolidShapesVector___getitem__}
       42    0.000    0.000    0.001    0.000 /home/gromualdi/robot-code/robot-log-visualizer/visualizer-env/lib/python3.8/site-packages/zmq/sugar/socket.py:549(send_multipart)
      966    0.000    0.000    0.000    0.000 {built-in method _struct.pack}
       42    0.000    0.000    0.000    0.000 {method 'dot' of 'numpy.ndarray' objects}
      966    0.000    0.000    0.000    0.000 {method 'write' of '_io.BytesIO' objects}

@GiulioRomualdi
Copy link
Member Author

Related to duburcqa/jiminy#543

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

3 participants