Intro
Hello,
I am a grad student using Mujoco to simulate a soft bodied robot made with the cable composite elements. Despite having the proper dimensions and Twist/Bend properties for the material I noticed my deflections were not matching the physical robot we used as our comparison point so I did a few tests and dove into the base code.
My setup
Mujoco, Python
What's happening? What did you expect?
In the plugin file cable.cc (https://github.com/google-deepmind/mujoco/blob/main/plugin/elasticity/cable.cc#L134) lines 180-201 show the area moment of inertia calculation for the cable elements. I have selected capsule in the xml code which should mean Iy, Iz, and J for the circular cross section are used (lines 184-185). However, when I run a simple beam bending test, maintaining small deflection to conserve the small angle approximation, it produces stiffness that lines up almost perfectly with the rectangular cross section equations of the box elements (lines 193-195). Is it possible that the if statement in line 180/181 is not being executed properly and is instead always doing the box geom calculations for some reason?
Steps for reproduction
- Put the python code (copied into a python file) and the xml model (in the Minimal Model section) in the same folder. Note that the model is attached as a txt file and will need to be copy/pasted into an xml file as xml is apparently not a supported attachment type.
- Run the code.
- You will see the rectangular area moment of inertia calculation and the measured area moment of inertia line up while the circular cross section, which should be used for the capsule type, is off by a lot.
Minimal model for reproduction
cable_xml.txt
Code required for reproduction
import numpy as np
import mujoco
import mediapy as media
import matplotlib.pyplot as plt
import os
import math
work_dir = os.getcwd()
xml_path = work_dir + r"\cable.xml"
model = mujoco.MjModel.from_xml_path(xml_path)
data = mujoco.MjData(model)
mujoco.mj_forward(model, data)
muscle_ind = 0 # might be 2??
tmax = 4
dt = 0.1/1000
t = np.arange(0, tmax, dt)
model.opt.timestep = dt
max_act = 0.01
force_app = 0.1
ctrl_ramp = np.ones(len(t))*max_act
ctrl_ramp[0:int(len(t)/8)] = np.linspace(0,max_act,int(len(t)/8))
frames = []
framerate = 60
muscle_force = np.zeros(np.size(t))
x_pos = np.zeros(np.size(t))
tendon_length = np.zeros(np.size(t))
slider_id = mujoco.mj_name2id(model,mujoco.mjtObj.mjOBJ_BODY,"slider")
for i in range(len(t)):
data.xfrc_applied[slider_id] = [force_app, 0, 0, 0, 0, 0]
mujoco.mj_step(model, data)
x_pos[i] = data.xpos[slider_id,0]
# print(ctrl_ramp)
E_mod = 3e8
# E_mod = 10e8
cable_L = 0.3
radius = 0.00299
I_calc = (math.pi/4)*pow(radius,4)
print("Calculated Area Moment of Inertia for Circular C/S: ", I_calc)
I_calc_sq = pow(2*radius,3)*2*radius/12
print("Calculated Area Moment of Inertia for Rectangular C/S: ", I_calc_sq)
print("Force = ", force_app)
Disp = np.max(x_pos)
print("Displacement = ", Disp)
I_meas = (force_app*pow(cable_L,3))/(Disp*3*E_mod)
print("Measured Area Moment of Inertia: ", I_meas)
Confirmations
Intro
Hello,
I am a grad student using Mujoco to simulate a soft bodied robot made with the cable composite elements. Despite having the proper dimensions and Twist/Bend properties for the material I noticed my deflections were not matching the physical robot we used as our comparison point so I did a few tests and dove into the base code.
My setup
Mujoco, Python
What's happening? What did you expect?
In the plugin file cable.cc (https://github.com/google-deepmind/mujoco/blob/main/plugin/elasticity/cable.cc#L134) lines 180-201 show the area moment of inertia calculation for the cable elements. I have selected capsule in the xml code which should mean Iy, Iz, and J for the circular cross section are used (lines 184-185). However, when I run a simple beam bending test, maintaining small deflection to conserve the small angle approximation, it produces stiffness that lines up almost perfectly with the rectangular cross section equations of the box elements (lines 193-195). Is it possible that the if statement in line 180/181 is not being executed properly and is instead always doing the box geom calculations for some reason?
Steps for reproduction
Minimal model for reproduction
cable_xml.txt
Code required for reproduction
Confirmations