How to avoid difference in contact model on box and plane #2199
-
IntroHi! I am a PhD student in Robotics Lab at IIT Kanpur, I use MuJoCo for my research on bipedal locomotion on deformable terrain. My setupI'm using MuJoCo version 3.1.6 in Python API. My questionRecently, I'm working on contact model parameters identification for foot-terrain interaction and facing issues in contact forces on box geometry. Here is the simple xml file for collision of sphere on a box:
This is the force vs deformation plot for this model: If I replace the box with a plane, I get this plot: Why the discontinuity of slope is there in the case of box? Is the contact model for box different from plane? Minimal model and/or code that explain my questionCode: import mujoco as mj
import mujoco.viewer
import numpy as np
import matplotlib.pyplot as plt
simend = 0.5 #simulation time
simfreq = 1000 # 100 fps
#xml_path= 'ball.xml'
xml= """
<mujoco>
<worldbody>
<!-- <geom name="terrain-plane" type="plane" pos="0 0 -0.0" size="0.5 0.5 0.01"/>-->
<geom name="floor1-box" type="box" pos = "0 0 -0.25" size="0.5 0.5 .25" />
<body name ="com" pos="0 0 -0.002" euler="0 0 0">
<joint type="free"/>
<geom type="sphere" pos="0 0 -0.0" mass="1" size="0.005" contype="1" conaffinity="1" rgba="1 0 0 1"/>
</body>
</worldbody>
<option timestep="0.00001" />
</mujoco>
"""
# MuJoCo data structures
#model = mj.MjModel.from_xml_path(xml_path) # MuJoCo model
model = mj.MjModel.from_xml_string(xml) # MuJoCo model
data = mj.MjData(model) # MuJoCo data
cam = mj.MjvCamera() # Abstract camera
opt = mj.MjvOption() # visualization options
# Plots
fig1=plt.figure(1)
fig2=plt.figure(2)
fig3=plt.figure(3)
#Sys identification
ttraj=[]
ftraj=[]
rtraj=[]
dtraj=[]
mtraj=[]
with mj.viewer.launch_passive(
model=model, data=data, show_left_ui=True, show_right_ui=False
) as viewer:
# Initialize the camera view to that of the free camera.
mj.mjv_defaultFreeCamera(model, viewer.cam)
while viewer.is_running() and data.time<simend:
time_prev = data.time
while (data.time - time_prev < 1.0 / simfreq):
mj.mj_step(model, data) #Forward dynamics
if (data.time >= simend):
break;
# contact force
fc = np.zeros([6])
for i in np.arange(0, data.ncon):
fci = np.zeros([6])
try:
mj.mj_contactForce(model, data, i, fci)
fc = fc + fci
except:
print('no contact')
#Save data for sys identification
ttraj.append(data.time)
ftraj.append(fc[0:3].copy())
rtraj.append(data.qpos[0:7].copy())
if data.ncon>0:
dtraj.append(data.efc_pos[0].copy())
mtraj.append(data.efc_margin[0].copy())
else:
dtraj.append(0)
mtraj.append(0)
# Update scene and render
viewer.opt.flags[16]=1
viewer.sync()
ttraj=np.array(ttraj)
rtraj=np.array(rtraj)
ftraj=np.array(ftraj)
dtraj=np.array(dtraj)
mtraj=np.array(mtraj)
plt.figure(1)
radius=model.geom_size[-1][0]
for i in np.arange(0,len(ttraj)):
if ftraj[i,0]>0 or (rtraj[i,2]-radius)<0:
plt.plot(abs(rtraj[i,2]-radius),ftraj[i,0],'.r')
plt.xlabel('Deformation (m)')
plt.ylabel('Normal Force (N)')
plt.grid(visible=None, which='major', axis='both')
plt.figure(2)
plt.plot(ttraj,ftraj[:,0],'.r')
plt.xlabel('Time (s)')
plt.ylabel('Normal Force (N)')
plt.grid(visible=None, which='major', axis='both')
plt.figure(3)
plt.plot(ttraj,rtraj[:,2],'.r',label='center of mass')
plt.plot(ttraj,mtraj[:],'.g',label='efc_margin')
plt.plot(ttraj,dtraj[:],'.b',label='efc_pos')
plt.xlabel('Time (s)')
plt.ylabel('Position (m)')
plt.grid(visible=None, which='major', axis='both')
plt.legend()
plt.show() Confirmations
|
Beta Was this translation helpful? Give feedback.
Replies: 1 comment
-
I looked into it, this is a bug in the box-sphere collider. See #2206 Also, look at my MRE therein, it might be useful. |
Beta Was this translation helpful? Give feedback.
I looked into it, this is a bug in the box-sphere collider. See #2206
Also, look at my MRE therein, it might be useful.