google-deepmind / mujoco

Multi-Joint dynamics with Contact. A general purpose physics simulator.
https://mujoco.org
Apache License 2.0
7.47k stars 734 forks source link

MuJoCo ROS Integration - segmentation faults in model instance (from version 3.1.1 -> ^3.1.2) #1698

Open peterdavidfagan opened 4 weeks ago

peterdavidfagan commented 4 weeks ago

Hi,

I'm a PhD student and I'm trying to use MuJoCo with ROS 2 to prototype robot workspaces and ROS 2 application software. I have created the following ROS package to accomplish this and it seems to work for MuJoCo version 3.1.1 and earlier. I recently have been looking to include meshes in my scenes which resulted in errors in 3.1.1 relating to inconsistent normals as seen here. As part of resolving this issue I looked to upgrade my MuJoCo version while in the process of doing so I have encountered segmentation faults when when interfacing with the model instance for all versions greater than or equal to 3.1.2.

I'm looking for some help with understanding changes between 3.1.1 -> 3.1.2 that may be causing my issue. I have started looking at the changelog and performing a diff to understand better what is causing my integration package to always produce a segfault on more recent versions of MuJoCo "^3.1.2". I am posting this issue in case anyone has a quick answer to what might be causing this issue in latest MuJoCo versions. I also believe this is relevant for anyone looking to cast model/data instances from python to C++ in a manner similar to the below:

std::uintptr_t m_raw = model.attr("_address").cast<std::uintptr_t>();
std::uintptr_t d_raw = data.attr("_address").cast<std::uintptr_t>();
m = reinterpret_cast<mjModel *>(m_raw);
d = reinterpret_cast<mjData *>(d_raw);

I instantiate my python binding from the referenced package in a Python script as below, where I read in the latest scene.xml from mujoco_menagerie for the Franka Emika Panda model:

import os
import time

import mujoco
import mujoco.viewer

import mujoco_ros
from mujoco_ros.franka_env import FrankaEnv

model_filepath = os.path.join(os.path.dirname(os.path.abspath(__file__)), 'models', 'franka_emika_panda', 'scene.xml')
print(model_filepath)

if __name__=="__main__":
    m = mujoco.MjModel.from_xml_path(model_filepath)
    d = mujoco.MjData(m)

    with mujoco.viewer.launch_passive(
        model=m, 
        data=d,
        show_left_ui=False,
        show_right_ui=False,
        ) as viewer:

        env = FrankaEnv(
        m, 
        d, 
        command_interface="effort",
        control_steps=5, 
        control_timer_freq=1e-2,
        )

        # run interactive viewer application
        while viewer.is_running():
            time.sleep(0.05)
            env.is_syncing = True
            viewer.sync()
            env.is_syncing = False  

This results in the following backtrace for the segfault:

(gdb) bt
#0  mj_kinematics (m=0x555555d63680, d=0x555555db2180) at /home/peter/Code/temp/ros2_robotics_research_toolkit/build/mujoco_ros_py/_deps/mujoco-src/src/engine/engine_core_smooth.c:82
#1  0x00007fffb84712a6 in mj_fwdPosition (m=0x555555d63680, d=0x555555db2180) at /home/peter/Code/temp/ros2_robotics_research_toolkit/build/mujoco_ros_py/_deps/mujoco-src/src/engine/engine_forward.c:127
#2  0x00007fffb847514a in mj_forwardSkip (m=0x555555d63680, d=0x555555db2180, skipstage=0, skipsensor=0)
    at /home/peter/Code/temp/ros2_robotics_research_toolkit/build/mujoco_ros_py/_deps/mujoco-src/src/engine/engine_forward.c:996
#3  0x00007fffb8475302 in mj_forward (m=0x555555d63680, d=0x555555db2180) at /home/peter/Code/temp/ros2_robotics_research_toolkit/build/mujoco_ros_py/_deps/mujoco-src/src/engine/engine_forward.c:1035
#4  0x00007fffb8a9311a in franka_table::FrankaTableEnv::init_scene (this=0x555555e723e0) at /home/peter/Code/temp/ros2_robotics_research_toolkit/src/mujoco/mujoco_ros/src/franka_table.cpp:208
#5  0x00007fffb8a91bac in franka_table::FrankaTableEnv::FrankaTableEnv (this=0x555555e723e0, model=..., data=..., command_interface="effort", control_steps=5, control_timer_freq=0.01)
    at /home/peter/Code/temp/ros2_robotics_research_toolkit/src/mujoco/mujoco_ros/src/franka_table.cpp:52
#6  0x00007fffb8a942dc in operator() (__closure=0x555555d61ce8, model=..., data=..., command_interface="effort", control_steps=5, control_timer_freq=0.01)
    at /home/peter/Code/temp/ros2_robotics_research_toolkit/src/mujoco/mujoco_ros/src/franka_table.cpp:353
#7  0x00007fffb8a94f47 in operator() (__closure=0x555555d61ce8, v_h=..., args#0=..., args#1=..., args#2="", args#3=5, args#4=0.01) at /usr/include/pybind11/detail/init.h:242
#8  0x00007fffb8a96efb in pybind11::detail::argument_loader<pybind11::detail::value_and_holder&, pybind11::object, pybind11::object, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, double>::call_impl<void, pybind11::detail::initimpl::factory<pybind11_init_franka_env(pybind11::module_&)::<lambda(pybind11::object, pybind11::object, std::string, int, double)>, pybind11::detail::void_type (*)(), std::shared_ptr<franka_table::FrankaTableEnv>(pybind11::object, pybind11::object, std::__cxx11::basic_string<char>, int, double), pybind11::detail::void_type()>::execute<pybind11::class_<franka_table::FrankaTableEnv, std::shared_ptr<franka_table::FrankaTableEnv> >, pybind11::arg, pybind11::arg, pybind11::arg_v, pybind11::arg_v, pybind11::arg_v, pybind11::return_value_policy, char [49]>(pybind11::class_<franka_table::FrankaTableEnv, std::shared_ptr<franka_table::FrankaTableEnv> >&, const pybind11::arg&, const pybind11::arg&, const pybind11::arg_v&, const pybind11::arg_v&, const pybind11::arg_v&, const pybind11::return_value_policy&, char const (&)[49]) &&::<lambda(pybind11::detail::value_and_holder&, pybind11::object, pybind11::object, std::__cxx11::basic_string<char>, int, double)>&, 0, 1, 2, 3, 4, 5, pybind11::detail::void_type>(struct {...} &, std::index_sequence, pybind11::detail::void_type &&) (this=0x7fffffff5630, f=...) at /usr/include/pybind11/cast.h:1207
#9  0x00007fffb8a96c8c in pybind11::detail::argument_loader<pybind11::detail::value_and_holder&, pybind11::object, pybind11::object, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, int, double>::call<void, pybind11::detail::void_type, pybind11::detail::initimpl::factory<pybind11_init_franka_env(pybind11::module_&)::<lambda(pybind11::object, pybind11::object, std::string, int, double)>, pybind11::detail::void_type (*)(), std::shared_ptr<franka_table::FrankaTableEnv>(pybind11::object, pybind11::object, std::__cxx11::basic_string<char>, int, double), pybind11::detail::void_type()>::execute<pybind11::class_<franka_table::FrankaTableEnv, std::shared_ptr<franka_table::FrankaTableEnv> >, pybind11::arg, pybind11::arg, pybind11::arg_v, pybind11::arg_v, pybind11::arg_v, pybind11::return_value_policy, char [49]>(pybind11::class_<franka_table::FrankaTableEnv, std::shared_ptr<franka_table::FrankaTableEnv> >&, const pybind11::arg&, const pybind11::arg&, const pybind11::arg_v&, const pybind11::arg_v&, const pybind11::arg_v&, const pybind11::return_value_policy&, char const (&)[49]) &&::<lambda(pybind11::detail::value_and_holder&, pybind11::object, pybind11::object, std::__cxx11::basic_string<char>, int, double)>&>(struct {...} &) (this=0x7fffffff5630, f=...) at /usr/include/pybind11/cast.h:1184
#10 0x00007fffb8a96347 in operator() (__closure=0x0, call=...) at /usr/include/pybind11/pybind11.h:233
#11 0x00007fffb8a963e8 in _FUN () at /usr/include/pybind11/pybind11.h:210
#12 0x00007fffb8aab20c in pybind11::cpp_function::dispatcher (self=0x7fffb8f2d470, args_in=0x7fffb8f26bc0, kwargs_in=0x7ffff37d2c40) at /usr/include/pybind11/pybind11.h:835
#13 0x00007ffff7b12713 in cfunction_call (func=0x7fffb8f32cf0, args=<optimised out>, kwargs=<optimised out>) at Objects/methodobject.c:543
#14 0x00007ffff7ac935c in _PyObject_MakeTpCall (tstate=0x55555557e350, callable=0x7fffb8f32cf0, args=<optimised out>, nargs=3, keywords=0x7fffb8f26a00) at Objects/call.c:215
#15 0x00007ffff7acc172 in _PyObject_VectorcallTstate (kwnames=0x7fffb8f26a00, nargsf=3, args=0x7fffb8f2dda0, callable=0x7fffb8f32cf0, tstate=0x55555557e350) at ./Include/cpython/abstract.h:112
#16 _PyObject_VectorcallTstate (kwnames=0x7fffb8f26a00, nargsf=3, args=0x7fffb8f2dda0, callable=0x7fffb8f32cf0, tstate=0x55555557e350) at ./Include/cpython/abstract.h:99
--Type <RET> for more, q to quit, c to continue without paging--
#17 method_vectorcall (method=<optimised out>, args=0x7fffb8f2dda8, nargsf=<optimised out>, kwnames=0x7fffb8f26a00) at Objects/classobject.c:53
#18 0x00007ffff7ac8fe8 in PyVectorcall_Call (callable=0x7ffff7391bc0, tuple=<optimised out>, kwargs=<optimised out>) at Objects/call.c:267
#19 0x00007ffff7b37202 in slot_tp_init (self=0x7ffff73e9830, args=0x7fffb63f9a00, kwds=0x7ffff7376980) at Objects/typeobject.c:7737
#20 0x00007ffff7b2ed3e in type_call (type=<optimised out>, args=0x7fffb63f9a00, kwds=0x7ffff7376980) at Objects/typeobject.c:1135
#21 0x00007fffb8aa5495 in pybind11::detail::pybind11_meta_call (type=0x555555d61db0, args=0x7fffb63f9a00, kwargs=0x7ffff7376980) at /usr/include/pybind11/detail/class.h:174
#22 0x00007ffff7ac935c in _PyObject_MakeTpCall (tstate=0x55555557e350, callable=0x555555d61db0, args=<optimised out>, nargs=2, keywords=0x7ffff75c4dc0) at Objects/call.c:215
#23 0x00007ffff7a72966 in _PyObject_VectorcallTstate (kwnames=0x7ffff75c4dc0, nargsf=9223372036854775810, args=0x7ffff7929bb0, callable=0x555555d61db0, tstate=<optimised out>)
    at ./Include/cpython/abstract.h:112
#24 _PyObject_VectorcallTstate (kwnames=0x7ffff75c4dc0, nargsf=9223372036854775810, args=0x7ffff7929bb0, callable=0x555555d61db0, tstate=<optimised out>) at ./Include/cpython/abstract.h:99
#25 PyObject_Vectorcall (kwnames=0x7ffff75c4dc0, nargsf=9223372036854775810, args=0x7ffff7929bb0, callable=0x555555d61db0) at ./Include/cpython/abstract.h:123
#26 call_function (kwnames=0x7ffff75c4dc0, oparg=<optimised out>, pp_stack=<synthetic pointer>, trace_info=0x7fffffff5e40, tstate=0x55555557e350) at Python/ceval.c:5891
#27 _PyEval_EvalFrameDefault (tstate=<optimised out>, f=<optimised out>, throwflag=<optimised out>) at Python/ceval.c:4231
#28 0x00007ffff7bbbaa0 in _PyEval_EvalFrame (throwflag=0, f=0x7ffff7929a40, tstate=0x55555557e350) at ./Include/internal/pycore_ceval.h:46
#29 _PyEval_Vector (kwnames=0x0, argcount=0, args=0x0, locals=0x7ffff754b900, con=0x7fffffff5f20, tstate=0x55555557e350) at Python/ceval.c:5065
#30 PyEval_EvalCode (co=co@entry=0x7ffff75c8b30, globals=globals@entry=0x7ffff754b900, locals=locals@entry=0x7ffff754b900) at Python/ceval.c:1134
#31 0x00007ffff7c022ad in run_eval_code_obj (locals=0x7ffff754b900, globals=0x7ffff754b900, co=0x7ffff75c8b30, tstate=0x55555557e350) at Python/pythonrun.c:1291
#32 run_mod (mod=<optimised out>, filename=filename@entry=0x7ffff75c90b0, globals=globals@entry=0x7ffff754b900, locals=locals@entry=0x7ffff754b900, flags=flags@entry=0x7fffffff6098, 
    arena=arena@entry=0x7ffff79feb70) at Python/pythonrun.c:1312
#33 0x00007ffff7c03476 in pyrun_file (flags=0x7fffffff6098, closeit=<optimised out>, locals=0x7ffff754b900, globals=0x7ffff754b900, start=257, filename=0x7ffff75c90b0, fp=0x555555559390)
    at Python/pythonrun.c:1208
#34 _PyRun_SimpleFileObject (fp=fp@entry=0x555555559390, filename=filename@entry=0x7ffff75c90b0, closeit=closeit@entry=1, flags=flags@entry=0x7fffffff6098) at Python/pythonrun.c:456
#35 0x00007ffff7c03a0f in _PyRun_AnyFileObject (fp=0x555555559390, filename=filename@entry=0x7ffff75c90b0, closeit=closeit@entry=1, flags=flags@entry=0x7fffffff6098) at Python/pythonrun.c:90
#36 0x00007ffff7c236e3 in pymain_run_file_obj (skip_source_first_line=0, filename=0x7ffff75c90b0, program_name=0x7ffff7939ae0) at Modules/main.c:353
#37 pymain_run_file (config=0x55555555f520) at Modules/main.c:372
#38 pymain_run_python (exitcode=0x7fffffff6090) at Modules/main.c:587
#39 Py_RunMain () at Modules/main.c:666
#40 0x00007ffff7c23fbe in pymain_main (args=0x7fffffff6190) at Modules/main.c:696
#41 Py_BytesMain (argc=<optimised out>, argv=<optimised out>) at Modules/main.c:720
#42 0x00007ffff7629d90 in __libc_start_call_main (main=main@entry=0x555555555060 <main>, argc=argc@entry=2, argv=argv@entry=0x7fffffff6318) at ../sysdeps/nptl/libc_start_call_main.h:58
#43 0x00007ffff7629e40 in __libc_start_main_impl (main=0x555555555060 <main>, argc=2, argv=0x7fffffff6318, init=<optimised out>, fini=<optimised out>, rtld_fini=<optimised out>, stack_end=0x7fffffff6308)
    at ../csu/libc-start.c:392
#44 0x0000555555555095 in _start ()
peterdavidfagan commented 4 weeks ago

For now I am going to pin my version to 3.1.1 as this seems like it will take me some time to read the diff and understand exactly what change caused the segfault (presumably changes to passive viewer).

In general, I am motivated to keep my package up to date with the latest releases as I intend to leverage this workflow throughout the remainder of my research studies. I'll update this issue when I get back to it.