Comments (10)
Any chance you could attach an example XML file where this happens?
Also, what is the number of cubes you create in your model?
from mujoco.
I randomly selected some voxels from a large voxel model and used them in mujoco. A part of my xml file is showed in here. And the number of cubess is more than 2000.<mujoco model="voxel_model"> <worldbody> <body name="voxel_22458"> <geom type="box" size="0.005 0.005 0.005" rgba="0.204 0.357 0.286 1" pos="-0.08 -0.08 0.0" contype="2" conaffinity="1"/> <joint name="voxel_22458" type="free" damping="0.1"/> </body> <body name="voxel_22459"> <geom type="box" size="0.005 0.005 0.005" rgba="0.239 0.369 0.329 1" pos="-0.07 -0.09 0.0" contype="2" conaffinity="1"/> <joint name="voxel_22459" type="free" damping="0.1"/> </body> <body name="voxel_22460"> <geom type="box" size="0.005 0.005 0.005" rgba="0.161 0.294 0.278 1" pos="-0.05 -0.1 0.0" contype="2" conaffinity="1"/> <joint name="voxel_22460" type="free" damping="0.1"/> </body> <body name="voxel_22461"> <geom type="box" size="0.005 0.005 0.005" rgba="0.161 0.294 0.278 1" pos="-0.04 -0.1 0.0" contype="2" conaffinity="1"/> <joint name="voxel_22461" type="free" damping="0.1"/> </body> <body name="voxel_23507"> <geom type="box" size="0.005 0.005 0.005" rgba="0.12 0.223 0.222 1" pos="0.07 -0.04 0.09" contype="2" conaffinity="1"/> <joint name="voxel_23507" type="free" damping="0.1"/> </body> ........
from mujoco.
One important change you should make to your model is to specify the pos
attribute on the body
and not the geom
tag.
Some computations are more efficient if the centre of mass of a body is aligned with the position of the body, which won't be the case in your model. There might be implications to collision detection too.
from mujoco.
When you say "more than 2000", do you mean a lot more? Can you give an exact number for when it fails, or at least an upper bound rather than a lower bound?
We have one O(nbody^2) stack allocation here, but 2000 would be way too small to account for the size of alloc you got in your error message (which suggests 27k voxels). Given the names of the voxels in your example I'll assume you meant 20000 rather than 2000. :)
from mujoco.
Thank you for your response. Upon reviewing my XML file, I realized that it contains 2276 cubes. Further inspection led me to discover that it's likely other components in the XML file, not related to the cubes, that are contributing to the increased memory usage. These components are parts of the robot.
Below, I've included a more detailed snippet of the XML code for your reference and a better understanding of the structure.
I hope this provides more clarity on the issue. I look forward to any suggestions or insights you might have regarding the memory allocation and how to optimize it.
`
<body name="frame">
<inertial diaginertia="222.35 143.37 209.67" mass="1e-2" pos="0 0 0.66" />
<geom name="frame" type="mesh" mesh="frame" pos="0 0 0" contype="0" conaffinity="0" />
<body name="wheel_rr" pos="-0.894 -0.633 0.206">
<inertial diaginertia="0.1 0.18 0.1" mass="1e-2" pos="0 0 0" />
<geom name="wheel_rr" type="mesh" mesh="wheel" pos="0 0 0" euler="0 0 3.14159" contype="0" conaffinity="0" />
<joint name="wheel_rr_joint" type="hinge" axis="0 -1 0" limited="false" damping="0.1" frictionloss="0.1" />
</body>
<body name="wheel_lr" pos="-0.894 0.633 0.206">
<inertial diaginertia="0.1 0.18 0.1" mass="1e-2" pos="0 0 0" />
<geom name="wheel_lr" type="mesh" mesh="wheel" pos="0 0 0" euler="0 0 3.14159" contype="0" conaffinity="0" />
<joint name="wheel_lr_joint" type="hinge" axis="0 -1 0" limited="false" damping="0.1" frictionloss="0.1" />
</body>
<body name="wheel_rf" pos="0.894 -0.633 0.206">
<inertial diaginertia="0.1 0.18 0.1" mass="1e-2" pos="0 0 0" />
<geom name="wheel_rf" type="mesh" mesh="wheel" pos="0 0 0" euler="0 0 0" contype="0" conaffinity="0" />
<joint name="wheel_rf_joint" type="hinge" axis="0 1 0" limited="false" damping="0.1" frictionloss="0.1" />
</body>
<body name="wheel_lf" pos="0.894 0.633 0.206">
<inertial diaginertia="0.1 0.18 0.1" mass="1e-2" pos="0 0 0" />
<geom name="wheel_lf" type="mesh" mesh="wheel" pos="0 0 0" euler="0 0 0" contype="0" conaffinity="0" />
<joint name="wheel_lf_joint" type="hinge" axis="0 1 0" limited="false" damping="0.1" frictionloss="0.1" />
</body>
<body name="Y_linear" pos="0 0 1.137">
<inertial diaginertia="1e-4 1e-4 1e-4" mass="1e-2" pos="0.01 -0.02 -0.1" />
<geom name="Y_linear" type="mesh" mesh="Y_linear" pos="0 0 0" contype="1" conaffinity="0" />
<joint name="Y_linear_joint" type="slide" axis="0 -1 0" pos="0 0 0" damping="0.1" frictionloss="0.1" limited="true" range="-0.3455 0.3455" />
<body name="X_linear" pos="0 0 -0.002">
<inertial diaginertia="1e-4 1e-4 1e-4" mass="1e-2" pos="-0.04 -0.01 -0.2" />
<geom name="X_linear" type="mesh" mesh="X_linear" pos="0 0 0" contype="1" conaffinity="0" />
<joint name="X_linear_joint" type="slide" axis="1 0 0" pos="0 0 0" damping="0.1" frictionloss="0.1" limited="true" range="-0.225 0.281" />
<body name="Z1_linear" pos="0 0 0">
<inertial diaginertia="1e-4 1e-4 1e-4" mass="1e-2" pos="-0.04 0 -0.24" />
<geom name="Z1_linear" type="mesh" mesh="Z1_linear" pos="0 0 0" contype="1" conaffinity="0" />
<joint name="Z1_linear_joint" type="slide" axis="0 0 -1" pos="0 0 0" damping="0.1" frictionloss="0.1" limited="true" range="0 0.276" />
<body name="Z2_linear" pos="0 0 0">
<inertial diaginertia="1e-4 1e-4 1e-4" mass="1e-2" pos="-0.01 0 -0.25" />
<geom name="Z2_linear" type="mesh" mesh="Z2_linear" pos="0 0 0" contype="1" conaffinity="0" />
<joint name="Z2_linear_joint" type="slide" axis="0 0 -1" pos="0 0 0" damping="0.1" frictionloss="0.1" limited="true" range="0 0.325" />
<body name="Z3_linear" pos="0 0 0.207">
<inertial diaginertia="1e-4 1e-4 1e-4" mass="1e-2" pos="0 0 0" />
<geom name="Z3_linear" type="mesh" mesh="Z3_linear" pos="0 0 0.207" contype="1" conaffinity="0" />
<joint name="Z3_linear_joint" type="slide" axis="0 0 -1" pos="0 0 0" damping="0.1" frictionloss="0.1" limited="true" range="0 0.415" />
<body name="yaw" pos="0 0 -0.657">
<inertial diaginertia="1e-4 1e-4 1e-4" mass="1e-2" pos="-0.01 -0.01 0.05" />
<geom name="yaw" type="mesh" mesh="yaw" pos="0 0 0" contype="1" conaffinity="0" />
<joint name="yaw_joint" type="hinge" axis="0 0 -1" pos="0 0 0" damping="0.1" frictionloss="0.1" limited="true" range="-180 180" />
<body name="pitch" pos="0 0 0">
<inertial diaginertia="1e-4 1e-4 1e-4" mass="1e-2" pos="0.05 0.01 0" />
<geom name="pitch" type="mesh" mesh="pitch" pos="0 0 0" contype="1" conaffinity="0" />
<joint name="pitch_joint" type="hinge" pos="0 0 0" axis="0 -1 0" damping="0.1" armature="0.01" frictionloss="0.1" limited="true" range="-180 30" />
<body name="harvest_tool" pos="0.114 0.0 0.0">
<inertial diaginertia="1e-4 1e-4 1e-4" mass="1e-2" pos="0.0 0.0 0.0" />
<geom name="harvest_tool" type="mesh" mesh="harvest_tool" pos="0 0 0" contype="1" conaffinity="0" />
</body>
</body>
<body name="subarm_base" pos="0.07325 0.0 0.076">
<inertial diaginertia="1e-4 1e-4 1e-4" mass="1e-2" pos="26.82e-03 -14.42e-03 18.28e-03" />
<geom name="subarm_base" type="mesh" mesh="subarm_base" pos="0 0 0" contype="1" conaffinity="0" />
<body name="joint1" pos="0.0 0.0 0.0">
<inertial diaginertia="1e-4 1e-4 1e-4" mass="1e-2" pos="96.28e-03 -3e-05 0" />
<geom name="joint1" type="mesh" mesh="joint1" pos="0 0 0" contype="1" conaffinity="0" />
<joint name="joint1_joint" type="hinge" pos="0 0 0" axis="0 0 1" damping="0.1" armature="0.01" frictionloss="0.1" limited="true" range="-115 115" />
<body name="joint2" pos="0.069 0.0 0.0">
<inertial diaginertia="1e-4 1e-4 1e-4" mass="1e-2" pos="8.26e-03 -1.4481e-01 3.7e-04" />
<geom name="joint2" type="mesh" mesh="joint2" pos="0 0 0" contype="1" conaffinity="0" />
<joint name="joint2_joint" type="hinge" pos="0 0 0" axis="0 1 0" damping="0.1" armature="0.01" frictionloss="0.1" limited="true" range="-115 115" />
<body name="joint3" pos="0.149 0.0 0.0">
<inertial diaginertia="1e-4 1e-4 1e-4" mass="1e-2" pos="1.507e-01 0.0 3.8e-04" />
<geom name="joint3" type="mesh" mesh="joint3" pos="0 0 0" contype="1" conaffinity="0" />
<joint name="joint3_joint" type="hinge" pos="0 0 0" axis="0 0 1" damping="0.1" armature="0.01" frictionloss="0.1" limited="true" range="-115 115" />
<body name="joint4" pos="0.149 0.0 0.0">
<inertial diaginertia="1e-4 1e-4 1e-4" mass="1e-2" pos="4.4206755e-02 3.6839985e-07 8.9142216e-03" />
<geom name="joint4" type="mesh" mesh="joint4" pos="0 0 0" contype="1" conaffinity="0" />
<joint name="joint4_joint" type="hinge" pos="0 0 0" axis="0 0 1" damping="0.1" armature="0.01" frictionloss="0.1" limited="true" range="-115 115" />
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>`
from mujoco.
`
<geom name="target" type="sphere" size="0.02" rgba="1 0 0 1" pos="0 0 0" contype="2" conaffinity="1" />
<joint name="target" type="free" damping="10" />
</body>
<body name="voxel_790">
<geom type="box" size="0.005 0.005 0.005" rgba="0.098 0.149 0.141 1" pos="0.16 0.07 0.41" contype="2" conaffinity="1" />
<joint name="voxel_790" type="free" damping="0.1" />
</body>
<body name="voxel_791">
<geom type="box" size="0.005 0.005 0.005" rgba="0.098 0.149 0.141 1" pos="0.17 0.07 0.41" contype="2" conaffinity="1" />
<joint name="voxel_791" type="free" damping="0.1" />
</body>
........2276 cubes`
and
<actuator> <motor name="wheel_rr_joint_motor" joint="wheel_rr_joint" ctrllimited="true" ctrlrange="-3.9 3.9" forcelimited="true" forcerange="-450 450" /> <motor name="wheel_lr_joint_motor" joint="wheel_lr_joint" ctrllimited="true" ctrlrange="-3.9 3.9" forcelimited="true" forcerange="-450 450" /> <motor name="wheel_rf_joint_motor" joint="wheel_rf_joint" ctrllimited="true" ctrlrange="-3.9 3.9" forcelimited="true" forcerange="-450 450" /> <motor name="wheel_lf_joint_motor" joint="wheel_lf_joint" ctrllimited="true" ctrlrange="-3.9 3.9" forcelimited="true" forcerange="-450 450" /> <position name="Y_linear_position" joint="Y_linear_joint" ctrllimited="true" ctrlrange="-0.3455 0.3455" forcelimited="true" forcerange="-230 230" /> <position name="X_linear_position" joint="X_linear_joint" ctrllimited="true" ctrlrange="-0.225 0.281" forcelimited="true" forcerange="-110 110" /> <position name="Z1_linear_position" joint="Z1_linear_joint" ctrllimited="true" ctrlrange="0 0.276" forcelimited="true" forcerange="-300 300" /> <position name="Z2_linear_position" joint="Z2_linear_joint" ctrllimited="true" ctrlrange="0 0.325" forcelimited="true" forcerange="-300 300" /> <position name="Z3_linear_position" joint="Z3_linear_joint" ctrllimited="true" ctrlrange="0 0.207" forcelimited="true" forcerange="-180 180" /> <position name="yaw_position" joint="yaw_joint" ctrllimited="true" ctrlrange="-3.14159 3.14159" forcelimited="true" forcerange="-1.7 1.7" /> <position name="pitch_position" joint="pitch_joint" ctrllimited="true" ctrlrange="-3.14159 0.523599" forcelimited="true" forcerange="-25 25" /> <position name="joint1_position" joint="joint1_joint" ctrllimited="true" ctrlrange="-2.01 2.01" forcelimited="true" forcerange="-25 25" /> <position name="joint2_position" joint="joint2_joint" ctrllimited="true" ctrlrange="-2.01 2.01" forcelimited="true" forcerange="-25 25" /> <position name="joint3_position" joint="joint3_joint" ctrllimited="true" ctrlrange="-2.01 2.01" forcelimited="true" forcerange="-25 25" /> <position name="joint4_position" joint="joint4_joint" ctrllimited="true" ctrlrange="-2.01 2.01" forcelimited="true" forcerange="-25 25" /> </actuator> <tendon /></mujoco>
from mujoco.
@kankanzheli If you can attach a zip file with a fully loadable XML model, that would make debugging this much easier.
from mujoco.
Did you try using <option solver="CG"/>
?
Currently the CG solver is the only one which is fully sparsified, this is mentioned in item 6 here
from mujoco.
I have attached the XML file below. To display the robot model, I need to call the stl file. I simplified the robot model. Each robot component is replaced by an identical rectangular prism (errors still occur).
1.zip
from mujoco.
Using option solver="CG" sloved my problem
from mujoco.
Related Issues (20)
- D4RL mujoco datasets compatibility between versions HOT 1
- MuJoCo cup model penetrating floor/table HOT 3
- Issues with Point Cloud Visibility in Camera's Field of View Using MuJoCo
- Document MJX "broadphase" fields
- Simulating tension only cables with variable lengths
- Disabling contact rendering for Touch Sensor Grid plugin HOT 1
- Human musculoskeletal motion simulation using mujoco HOT 1
- Build from Source incl. Python Bindings HOT 1
- unity 'mujoco.elasticity.cable' error HOT 2
- `mj_copyData` not copying contact details? HOT 3
- Getting contact information and z-position from external rendering software HOT 2
- Changing the geom mass fails to affect simulation properties? HOT 2
- How to set free joint in keyframe
- Saving the xml with updates after mj_step HOT 1
- Transforming contact forces from the contact frame to the local frame of a geom involved in said contact/collision? HOT 3
- differentiable physics tutorial missing module brax HOT 1
- Error: engine error: edge ordering is incoherent between flex and plugin / mujoco.elasticity.solid
- Using gmsh files in MuJoCo - XML Error: Error: Node tags must be sequential HOT 1
- Rotation of 3 hinge joints with orthogonal axes. HOT 2
- Gravity: Blocks not falling HOT 2
Recommend Projects
-
React
A declarative, efficient, and flexible JavaScript library for building user interfaces.
-
Vue.js
🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.
-
Typescript
TypeScript is a superset of JavaScript that compiles to clean JavaScript output.
-
TensorFlow
An Open Source Machine Learning Framework for Everyone
-
Django
The Web framework for perfectionists with deadlines.
-
Laravel
A PHP framework for web artisans
-
D3
Bring data to life with SVG, Canvas and HTML. 📊📈🎉
-
Recommend Topics
-
javascript
JavaScript (JS) is a lightweight interpreted programming language with first-class functions.
-
web
Some thing interesting about web. New door for the world.
-
server
A server is a program made to process requests and deliver data to clients.
-
Machine learning
Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.
-
Visualization
Some thing interesting about visualization, use data art
-
Game
Some thing interesting about game, make everyone happy.
Recommend Org
-
Facebook
We are working to build community through open source technology. NB: members must have two-factor auth.
-
Microsoft
Open source projects and samples from Microsoft.
-
Google
Google ❤️ Open Source for everyone.
-
Alibaba
Alibaba Open Source for everyone
-
D3
Data-Driven Documents codes.
-
Tencent
China tencent open source team.
from mujoco.