mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-12 21:00:11 +00:00
First step towards a MuJoCo MJCF importer for Bullet. It can load the humanoid.xml, ant.xml and some other OpenAI GYM asset files. Not all fields are converted, so it is work-in-progress. This is useful for Reinforcement Learning experiments, and would also help integration with DeepMind Lab.
This commit is contained in:
parent
7b9d194bfd
commit
fdd517e00f
80
data/mjcf/ant.xml
Normal file
80
data/mjcf/ant.xml
Normal file
@ -0,0 +1,80 @@
|
||||
<mujoco model="ant">
|
||||
<compiler angle="degree" coordinate="local" inertiafromgeom="true"/>
|
||||
<option integrator="RK4" timestep="0.01"/>
|
||||
<custom>
|
||||
<numeric data="0.0 0.0 0.55 1.0 0.0 0.0 0.0 0.0 1.0 0.0 -1.0 0.0 -1.0 0.0 1.0" name="init_qpos"/>
|
||||
</custom>
|
||||
<default>
|
||||
<joint armature="1" damping="1" limited="true"/>
|
||||
<geom conaffinity="0" condim="3" density="5.0" friction="1 0.5 0.5" margin="0.01" rgba="0.8 0.6 0.4 1"/>
|
||||
</default>
|
||||
<asset>
|
||||
<texture builtin="gradient" height="100" rgb1="1 1 1" rgb2="0 0 0" type="skybox" width="100"/>
|
||||
<texture builtin="flat" height="1278" mark="cross" markrgb="1 1 1" name="texgeom" random="0.01" rgb1="0.8 0.6 0.4" rgb2="0.8 0.6 0.4" type="cube" width="127"/>
|
||||
<texture builtin="checker" height="100" name="texplane" rgb1="0 0 0" rgb2="0.8 0.8 0.8" type="2d" width="100"/>
|
||||
<material name="MatPlane" reflectance="0.5" shininess="1" specular="1" texrepeat="60 60" texture="texplane"/>
|
||||
<material name="geom" texture="texgeom" texuniform="true"/>
|
||||
</asset>
|
||||
<worldbody>
|
||||
<light cutoff="100" diffuse="1 1 1" dir="-0 0 -1.3" directional="true" exponent="1" pos="0 0 1.3" specular=".1 .1 .1"/>
|
||||
<geom conaffinity="1" condim="3" material="MatPlane" name="floor" pos="0 0 0" rgba="0.8 0.9 0.8 1" size="40 40 40" type="plane"/>
|
||||
<body name="torso" pos="0 0 0.75">
|
||||
<geom name="torso_geom" pos="0 0 0" size="0.25" type="sphere"/>
|
||||
<joint armature="0" damping="0" limited="false" margin="0.01" name="root" pos="0 0 0" type="free"/>
|
||||
<body name="front_left_leg" pos="0 0 0">
|
||||
<geom fromto="0.0 0.0 0.0 0.2 0.2 0.0" name="aux_1_geom" size="0.08" type="capsule"/>
|
||||
<body name="aux_1" pos="0.2 0.2 0">
|
||||
<joint axis="0 0 1" name="hip_1" pos="0.0 0.0 0.0" range="-30 30" type="hinge"/>
|
||||
<geom fromto="0.0 0.0 0.0 0.2 0.2 0.0" name="left_leg_geom" size="0.08" type="capsule"/>
|
||||
<body pos="0.2 0.2 0">
|
||||
<joint axis="-1 1 0" name="ankle_1" pos="0.0 0.0 0.0" range="30 70" type="hinge"/>
|
||||
<geom fromto="0.0 0.0 0.0 0.4 0.4 0.0" name="left_ankle_geom" size="0.08" type="capsule"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="front_right_leg" pos="0 0 0">
|
||||
<geom fromto="0.0 0.0 0.0 -0.2 0.2 0.0" name="aux_2_geom" size="0.08" type="capsule"/>
|
||||
<body name="aux_2" pos="-0.2 0.2 0">
|
||||
<joint axis="0 0 1" name="hip_2" pos="0.0 0.0 0.0" range="-30 30" type="hinge"/>
|
||||
<geom fromto="0.0 0.0 0.0 -0.2 0.2 0.0" name="right_leg_geom" size="0.08" type="capsule"/>
|
||||
<body pos="-0.2 0.2 0">
|
||||
<joint axis="1 1 0" name="ankle_2" pos="0.0 0.0 0.0" range="-70 -30" type="hinge"/>
|
||||
<geom fromto="0.0 0.0 0.0 -0.4 0.4 0.0" name="right_ankle_geom" size="0.08" type="capsule"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="back_leg" pos="0 0 0">
|
||||
<geom fromto="0.0 0.0 0.0 -0.2 -0.2 0.0" name="aux_3_geom" size="0.08" type="capsule"/>
|
||||
<body name="aux_3" pos="-0.2 -0.2 0">
|
||||
<joint axis="0 0 1" name="hip_3" pos="0.0 0.0 0.0" range="-30 30" type="hinge"/>
|
||||
<geom fromto="0.0 0.0 0.0 -0.2 -0.2 0.0" name="back_leg_geom" size="0.08" type="capsule"/>
|
||||
<body pos="-0.2 -0.2 0">
|
||||
<joint axis="-1 1 0" name="ankle_3" pos="0.0 0.0 0.0" range="-70 -30" type="hinge"/>
|
||||
<geom fromto="0.0 0.0 0.0 -0.4 -0.4 0.0" name="third_ankle_geom" size="0.08" type="capsule"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name="right_back_leg" pos="0 0 0">
|
||||
<geom fromto="0.0 0.0 0.0 0.2 -0.2 0.0" name="aux_4_geom" size="0.08" type="capsule"/>
|
||||
<body name="aux_4" pos="0.2 -0.2 0">
|
||||
<joint axis="0 0 1" name="hip_4" pos="0.0 0.0 0.0" range="-30 30" type="hinge"/>
|
||||
<geom fromto="0.0 0.0 0.0 0.2 -0.2 0.0" name="rightback_leg_geom" size="0.08" type="capsule"/>
|
||||
<body pos="0.2 -0.2 0">
|
||||
<joint axis="1 1 0" name="ankle_4" pos="0.0 0.0 0.0" range="30 70" type="hinge"/>
|
||||
<geom fromto="0.0 0.0 0.0 0.4 -0.4 0.0" name="fourth_ankle_geom" size="0.08" type="capsule"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
<actuator>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" joint="hip_4" gear="150"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" joint="ankle_4" gear="150"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" joint="hip_1" gear="150"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" joint="ankle_1" gear="150"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" joint="hip_2" gear="150"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" joint="ankle_2" gear="150"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" joint="hip_3" gear="150"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" joint="ankle_3" gear="150"/>
|
||||
</actuator>
|
||||
</mujoco>
|
13
data/mjcf/capsule.xml
Normal file
13
data/mjcf/capsule.xml
Normal file
@ -0,0 +1,13 @@
|
||||
<!--
|
||||
MuJoCo MJCF test file. See http://mujoco.org/book/index.html
|
||||
-->
|
||||
<mujoco>
|
||||
<worldbody>
|
||||
<light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1"/>
|
||||
<geom type="plane" size="1 1 0.1" rgba=".9 0 0 1"/>
|
||||
<body pos="0 0 1">
|
||||
<joint type="free"/>
|
||||
<geom fromto="0.0 0.0 0.0 0. 0.2 0.0" name="aux_1_geom" size="0.05" type="capsule"/>
|
||||
</body>
|
||||
</worldbody>
|
||||
</mujoco>
|
13
data/mjcf/hello_mjcf.xml
Normal file
13
data/mjcf/hello_mjcf.xml
Normal file
@ -0,0 +1,13 @@
|
||||
<!--
|
||||
MuJoCo MJCF test file. See http://mujoco.org/book/index.html
|
||||
-->
|
||||
<mujoco>
|
||||
<worldbody>
|
||||
<light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1"/>
|
||||
<geom type="plane" size="1 1 0.1" rgba=".9 0 0 1"/>
|
||||
<body pos="0 0 1">
|
||||
<joint type="free"/>
|
||||
<geom type="box" size=".1 .2 .3" rgba="0 .9 0 1"/>
|
||||
</body>
|
||||
</worldbody>
|
||||
</mujoco>
|
44
data/mjcf/hopper.xml
Normal file
44
data/mjcf/hopper.xml
Normal file
@ -0,0 +1,44 @@
|
||||
<mujoco model="hopper">
|
||||
<compiler angle="degree" coordinate="global" inertiafromgeom="true"/>
|
||||
<default>
|
||||
<joint armature="1" damping="1" />
|
||||
<geom conaffinity="1" condim="1" contype="1" margin="0.001" material="geom" rgba="0.8 0.6 .4 1" solimp=".8 .8 .01" solref=".02 1"/>
|
||||
<motor ctrllimited="true" ctrlrange="-.4 .4"/>
|
||||
</default>
|
||||
<option integrator="RK4" timestep="0.002"/>
|
||||
<worldbody>
|
||||
<light cutoff="100" diffuse="1 1 1" dir="-0 0 -1.3" directional="true" exponent="1" pos="0 0 1.3" specular=".1 .1 .1"/>
|
||||
<geom conaffinity="1" condim="3" name="floor" pos="0 0 0" rgba="0.8 0.9 0.8 1" size="20 20 .125" type="plane" material="MatPlane"/>
|
||||
<body name="torso" pos="0 0 1.25">
|
||||
<joint armature="0" axis="1 0 0" damping="0" limited="false" name="rootx" pos="0 0 0" stiffness="0" type="slide"/>
|
||||
<joint armature="0" axis="0 0 1" damping="0" limited="false" name="rootz" pos="0 0 0" ref="1.25" stiffness="0" type="slide"/>
|
||||
<joint armature="0" axis="0 1 0" damping="0" limited="false" name="rooty" pos="0 0 1.25" stiffness="0" type="hinge"/>
|
||||
<geom friction="0.9" fromto="0 0 1.45 0 0 1.05" name="torso_geom" size="0.05" type="capsule"/>
|
||||
<body name="thigh" pos="0 0 1.05">
|
||||
<joint axis="0 -1 0" name="thigh_joint" pos="0 0 1.05" range="-150 0" type="hinge"/>
|
||||
<geom friction="0.9" fromto="0 0 1.05 0 0 0.6" name="thigh_geom" size="0.05" type="capsule"/>
|
||||
<body name="leg" pos="0 0 0.35">
|
||||
<joint axis="0 -1 0" name="leg_joint" pos="0 0 0.6" range="-150 0" type="hinge"/>
|
||||
<geom friction="0.9" fromto="0 0 0.6 0 0 0.1" name="leg_geom" size="0.04" type="capsule"/>
|
||||
<body name="foot" pos="0.13/2 0 0.1">
|
||||
<joint axis="0 -1 0" name="foot_joint" pos="0 0 0.1" range="-45 45" type="hinge"/>
|
||||
<geom friction="2.0" fromto="-0.13 0 0.1 0.26 0 0.1" name="foot_geom" size="0.06" type="capsule"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
<actuator>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="200.0" joint="thigh_joint"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="200.0" joint="leg_joint"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="200.0" joint="foot_joint"/>
|
||||
</actuator>
|
||||
<asset>
|
||||
<texture type="skybox" builtin="gradient" rgb1=".4 .5 .6" rgb2="0 0 0"
|
||||
width="100" height="100"/>
|
||||
<texture builtin="flat" height="1278" mark="cross" markrgb="1 1 1" name="texgeom" random="0.01" rgb1="0.8 0.6 0.4" rgb2="0.8 0.6 0.4" type="cube" width="127"/>
|
||||
<texture builtin="checker" height="100" name="texplane" rgb1="0 0 0" rgb2="0.8 0.8 0.8" type="2d" width="100"/>
|
||||
<material name="MatPlane" reflectance="0.5" shininess="1" specular="1" texrepeat="60 60" texture="texplane"/>
|
||||
<material name="geom" texture="texgeom" texuniform="true"/>
|
||||
</asset>
|
||||
</mujoco>
|
130
data/mjcf/humanoid.xml
Normal file
130
data/mjcf/humanoid.xml
Normal file
@ -0,0 +1,130 @@
|
||||
<mujoco model='humanoid'>
|
||||
<compiler inertiafromgeom='true' angle='degree'/>
|
||||
|
||||
<default>
|
||||
<joint limited='true' damping='1' armature='0' />
|
||||
<geom contype='1' conaffinity='1' condim='1' rgba='0.8 0.6 .4 1'
|
||||
margin="0.001" solref=".02 1" solimp=".8 .8 .01" material="geom"/>
|
||||
<motor ctrlrange='-.4 .4' ctrllimited='true'/>
|
||||
</default>
|
||||
|
||||
<option timestep='0.002' iterations="50" solver="PGS">
|
||||
<flag energy="enable"/>
|
||||
</option>
|
||||
|
||||
<visual>
|
||||
<map fogstart="3" fogend="5" force="0.1"/>
|
||||
<quality shadowsize="2048"/>
|
||||
</visual>
|
||||
|
||||
<asset>
|
||||
<texture type="skybox" builtin="gradient" width="100" height="100" rgb1=".4 .6 .8"
|
||||
rgb2="0 0 0"/>
|
||||
<texture name="texgeom" type="cube" builtin="flat" mark="cross" width="127" height="1278"
|
||||
rgb1="0.8 0.6 0.4" rgb2="0.8 0.6 0.4" markrgb="1 1 1" random="0.01"/>
|
||||
<texture name="texplane" type="2d" builtin="checker" rgb1=".2 .3 .4" rgb2=".1 0.15 0.2"
|
||||
width="100" height="100"/>
|
||||
|
||||
<material name='MatPlane' reflectance='0.5' texture="texplane" texrepeat="1 1" texuniform="true"/>
|
||||
<material name='geom' texture="texgeom" texuniform="true"/>
|
||||
</asset>
|
||||
|
||||
<worldbody>
|
||||
<geom name='floor' pos='0 0 0' size='10 10 0.125' type='plane' material="MatPlane" condim='3'/>
|
||||
|
||||
<body name='torso' pos='0 0 1.4'>
|
||||
<light mode='trackcom' directional='false' diffuse='.8 .8 .8' specular='0.3 0.3 0.3' pos='0 0 4.0' dir='0 0 -1'/>
|
||||
|
||||
|
||||
<geom name='torso1' type='capsule' fromto='0 -.07 0 0 .07 0' size='0.07' />
|
||||
<geom name='head' type='sphere' pos='0 0 .19' size='.09'/>
|
||||
<geom name='uwaist' type='capsule' fromto='-.01 -.06 -.12 -.01 .06 -.12' size='0.06'/>
|
||||
<body name='lwaist' pos='-.01 0 -0.260' quat='1.000 0 -0.002 0' >
|
||||
<geom name='lwaist' type='capsule' fromto='0 -.06 0 0 .06 0' size='0.06' />
|
||||
<joint name='abdomen_z' type='hinge' pos='0 0 0.065' axis='0 0 1' range='-45 45' damping='5' stiffness='20' armature='0.02' />
|
||||
<joint name='abdomen_y' type='hinge' pos='0 0 0.065' axis='0 1 0' range='-75 30' damping='5' stiffness='10' armature='0.02' />
|
||||
<body name='pelvis' pos='0 0 -0.165' quat='1.000 0 -0.002 0' >
|
||||
<joint name='abdomen_x' type='hinge' pos='0 0 0.1' axis='1 0 0' range='-35 35' damping='5' stiffness='10' armature='0.02' />
|
||||
<geom name='butt' type='capsule' fromto='-.02 -.07 0 -.02 .07 0' size='0.09' />
|
||||
<body name='right_thigh' pos='0 -0.1 -0.04' >
|
||||
<joint name='right_hip_x' type='hinge' pos='0 0 0' axis='1 0 0' range='-25 5' damping='5' stiffness='10' armature='0.01' />
|
||||
<joint name='right_hip_z' type='hinge' pos='0 0 0' axis='0 0 1' range='-60 35' damping='5' stiffness='10' armature='0.01' />
|
||||
<joint name='right_hip_y' type='hinge' pos='0 0 0' axis='0 1 0' range='-110 20' damping='5' stiffness='20' armature='0.0080' />
|
||||
<geom name='right_thigh1' type='capsule' fromto='0 0 0 0 0.01 -.34' size='0.06' />
|
||||
<body name='right_shin' pos='0 0.01 -0.403' >
|
||||
<joint name='right_knee' type='hinge' pos='0 0 .02' axis='0 -1 0' range='-160 -2' armature='0.0060' />
|
||||
<geom name='right_shin1' type='capsule' fromto='0 0 0 0 0 -.3' size='0.049' />
|
||||
<body name='right_foot' pos='0 0 -.39' >
|
||||
<joint name='right_ankle_y' type='hinge' pos='0 0 0.08' axis='0 1 0' range='-50 50' stiffness='4' armature='0.0008' />
|
||||
<joint name='right_ankle_x' type='hinge' pos='0 0 0.04' axis='1 0 0.5' range='-50 50' stiffness='1' armature='0.0006' />
|
||||
<geom name='right_foot_cap1' type='capsule' fromto='-.07 -0.02 0 0.14 -0.04 0' size='0.027' />
|
||||
<geom name='right_foot_cap2' type='capsule' fromto='-.07 0 0 0.14 0.02 0' size='0.027' />
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name='left_thigh' pos='0 0.1 -0.04' >
|
||||
<joint name='left_hip_x' type='hinge' pos='0 0 0' axis='-1 0 0' range='-25 5' damping='5' stiffness='10' armature='0.01' />
|
||||
<joint name='left_hip_z' type='hinge' pos='0 0 0' axis='0 0 -1' range='-60 35' damping='5' stiffness='10' armature='0.01' />
|
||||
<joint name='left_hip_y' type='hinge' pos='0 0 0' axis='0 1 0' range='-120 20' damping='5' stiffness='20' armature='0.01' />
|
||||
<geom name='left_thigh1' type='capsule' fromto='0 0 0 0 -0.01 -.34' size='0.06' />
|
||||
<body name='left_shin' pos='0 -0.01 -0.403' >
|
||||
<joint name='left_knee' type='hinge' pos='0 0 .02' axis='0 -1 0' range='-160 -2' stiffness='1' armature='0.0060' />
|
||||
<geom name='left_shin1' type='capsule' fromto='0 0 0 0 0 -.3' size='0.049' />
|
||||
<body name='left_foot' pos='0 0 -.39' >
|
||||
<joint name='left_ankle_y' type='hinge' pos='0 0 0.08' axis='0 1 0' range='-50 50' stiffness='4' armature='0.0008' />
|
||||
<joint name='left_ankle_x' type='hinge' pos='0 0 0.04' axis='1 0 0.5' range='-50 50' stiffness='1' armature='0.0006' />
|
||||
<geom name='left_foot_cap1' type='capsule' fromto='-.07 0.02 0 0.14 0.04 0' size='0.027' />
|
||||
<geom name='left_foot_cap2' type='capsule' fromto='-.07 0 0 0.14 -0.02 0' size='0.027' />
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<body name='right_upper_arm' pos='0 -0.17 0.06' >
|
||||
<joint name='right_shoulder1' type='hinge' pos='0 0 0' axis='2 1 1' range='-85 60' stiffness='1' armature='0.0068' />
|
||||
<joint name='right_shoulder2' type='hinge' pos='0 0 0' axis='0 -1 1' range='-85 60' stiffness='1' armature='0.0051' />
|
||||
<geom name='right_uarm1' type='capsule' fromto='0 0 0 .16 -.16 -.16' size='0.04 0.16' />
|
||||
<body name='right_lower_arm' pos='.18 -.18 -.18' >
|
||||
<joint name='right_elbow' type='hinge' pos='0 0 0' axis='0 -1 1' range='-90 50' stiffness='0' armature='0.0028' />
|
||||
<geom name='right_larm' type='capsule' fromto='0.01 0.01 0.01 .17 .17 .17' size='0.031' />
|
||||
<geom name='right_hand' type='sphere' pos='.18 .18 .18' size='0.04'/>
|
||||
</body>
|
||||
</body>
|
||||
<body name='left_upper_arm' pos='0 0.17 0.06' >
|
||||
<joint name='left_shoulder1' type='hinge' pos='0 0 0' axis='2 -1 1' range='-60 85' stiffness='1' armature='0.0068' />
|
||||
<joint name='left_shoulder2' type='hinge' pos='0 0 0' axis='0 1 1' range='-60 85' stiffness='1' armature='0.0051' />
|
||||
<geom name='left_uarm1' type='capsule' fromto='0 0 0 .16 .16 -.16' size='0.04 0.16' />
|
||||
<body name='left_lower_arm' pos='.18 .18 -.18' >
|
||||
<joint name='left_elbow' type='hinge' pos='0 0 0' axis='0 -1 -1' range='-90 50' stiffness='0' armature='0.0028' />
|
||||
<geom name='left_larm' type='capsule' fromto='0.01 -0.01 0.01 .17 -.17 .17' size='0.031' />
|
||||
<geom name='left_hand' type='sphere' pos='.18 -.18 .18' size='0.04'/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
|
||||
<actuator>
|
||||
<motor name='abdomen_y' gear='200' joint='abdomen_y' />
|
||||
<motor name='abdomen_z' gear='200' joint='abdomen_z' />
|
||||
<motor name='abdomen_x' gear='200' joint='abdomen_x' />
|
||||
<motor name='right_hip_x' gear='200' joint='right_hip_x' />
|
||||
<motor name='right_hip_z' gear='200' joint='right_hip_z' />
|
||||
<motor name='right_hip_y' gear='600' joint='right_hip_y' />
|
||||
<motor name='right_knee' gear='400' joint='right_knee' />
|
||||
<motor name='right_ankle_x' gear='100' joint='right_ankle_x' />
|
||||
<motor name='right_ankle_y' gear='100' joint='right_ankle_y' />
|
||||
<motor name='left_hip_x' gear='200' joint='left_hip_x' />
|
||||
<motor name='left_hip_z' gear='200' joint='left_hip_z' />
|
||||
<motor name='left_hip_y' gear='600' joint='left_hip_y' />
|
||||
<motor name='left_knee' gear='400' joint='left_knee' />
|
||||
<motor name='left_ankle_x' gear='100' joint='left_ankle_x' />
|
||||
<motor name='left_ankle_y' gear='100' joint='left_ankle_y' />
|
||||
<motor name='right_shoulder1' gear='100' joint='right_shoulder1' />
|
||||
<motor name='right_shoulder2' gear='100' joint='right_shoulder2' />
|
||||
<motor name='right_elbow' gear='200' joint='right_elbow' />
|
||||
<motor name='left_shoulder1' gear='100' joint='left_shoulder1' />
|
||||
<motor name='left_shoulder2' gear='100' joint='left_shoulder2' />
|
||||
<motor name='left_elbow' gear='200' joint='left_elbow' />
|
||||
</actuator>
|
||||
|
||||
</mujoco>
|
39
data/mjcf/reacher.xml
Normal file
39
data/mjcf/reacher.xml
Normal file
@ -0,0 +1,39 @@
|
||||
<mujoco model="reacher">
|
||||
<compiler angle="radian" inertiafromgeom="true"/>
|
||||
<default>
|
||||
<joint armature="1" damping="1" limited="true"/>
|
||||
<geom contype="0" friction="1 0.1 0.1" rgba="0.7 0.7 0 1"/>
|
||||
</default>
|
||||
<option gravity="0 0 -9.81" integrator="RK4" timestep="0.01"/>
|
||||
<worldbody>
|
||||
<!-- Arena -->
|
||||
<geom conaffinity="0" contype="0" name="ground" pos="0 0 0" rgba="0.9 0.9 0.9 1" size="1 1 10" type="plane"/>
|
||||
<geom conaffinity="0" fromto="-.3 -.3 .01 .3 -.3 .01" name="sideS" rgba="0.9 0.4 0.6 1" size=".02" type="capsule"/>
|
||||
<geom conaffinity="0" fromto=" .3 -.3 .01 .3 .3 .01" name="sideE" rgba="0.9 0.4 0.6 1" size=".02" type="capsule"/>
|
||||
<geom conaffinity="0" fromto="-.3 .3 .01 .3 .3 .01" name="sideN" rgba="0.9 0.4 0.6 1" size=".02" type="capsule"/>
|
||||
<geom conaffinity="0" fromto="-.3 -.3 .01 -.3 .3 .01" name="sideW" rgba="0.9 0.4 0.6 1" size=".02" type="capsule"/>
|
||||
<!-- Arm -->
|
||||
<geom conaffinity="0" contype="0" fromto="0 0 0 0 0 0.02" name="root" rgba="0.9 0.4 0.6 1" size=".011" type="cylinder"/>
|
||||
<body name="body0" pos="0 0 .01">
|
||||
<geom fromto="0 0 0 0.1 0 0" name="link0" rgba="0.0 0.4 0.6 1" size=".01" type="capsule"/>
|
||||
<joint axis="0 0 1" limited="false" name="joint0" pos="0 0 0" type="hinge"/>
|
||||
<body name="body1" pos="0.1 0 0">
|
||||
<joint axis="0 0 1" limited="true" name="joint1" pos="0 0 0" range="-3.0 3.0" type="hinge"/>
|
||||
<geom fromto="0 0 0 0.1 0 0" name="link1" rgba="0.0 0.4 0.6 1" size=".01" type="capsule"/>
|
||||
<body name="fingertip" pos="0.11 0 0">
|
||||
<geom contype="0" name="fingertip" pos="0 0 0" rgba="0.0 0.8 0.6 1" size=".01" type="sphere"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
<!-- Target -->
|
||||
<body name="target" pos=".1 -.1 .01">
|
||||
<joint armature="0" axis="1 0 0" damping="0" limited="true" name="target_x" pos="0 0 0" range="-.27 .27" ref=".1" stiffness="0" type="slide"/>
|
||||
<joint armature="0" axis="0 1 0" damping="0" limited="true" name="target_y" pos="0 0 0" range="-.27 .27" ref="-.1" stiffness="0" type="slide"/>
|
||||
<geom conaffinity="0" contype="0" name="target" pos="0 0 0" rgba="0.9 0.2 0.2 1" size=".009" type="sphere"/>
|
||||
</body>
|
||||
</worldbody>
|
||||
<actuator>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="200.0" joint="joint0"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1.0 1.0" gear="200.0" joint="joint1"/>
|
||||
</actuator>
|
||||
</mujoco>
|
38
data/mjcf/swimmer.xml
Normal file
38
data/mjcf/swimmer.xml
Normal file
@ -0,0 +1,38 @@
|
||||
<mujoco model="swimmer">
|
||||
<compiler angle="degree" coordinate="local" inertiafromgeom="true"/>
|
||||
<option collision="predefined" density="4000" integrator="RK4" timestep="0.01" viscosity="0.1"/>
|
||||
<default>
|
||||
<geom conaffinity="1" condim="1" contype="1" material="geom" rgba="0.8 0.6 .4 1"/>
|
||||
<joint armature='0.1' />
|
||||
</default>
|
||||
<asset>
|
||||
<texture builtin="gradient" height="100" rgb1="1 1 1" rgb2="0 0 0" type="skybox" width="100"/>
|
||||
<texture builtin="flat" height="1278" mark="cross" markrgb="1 1 1" name="texgeom" random="0.01" rgb1="0.8 0.6 0.4" rgb2="0.8 0.6 0.4" type="cube" width="127"/>
|
||||
<texture builtin="checker" height="100" name="texplane" rgb1="0 0 0" rgb2="0.8 0.8 0.8" type="2d" width="100"/>
|
||||
<material name="MatPlane" reflectance="0.5" shininess="1" specular="1" texrepeat="30 30" texture="texplane"/>
|
||||
<material name="geom" texture="texgeom" texuniform="true"/>
|
||||
</asset>
|
||||
<worldbody>
|
||||
<light cutoff="100" diffuse="1 1 1" dir="-0 0 -1.3" directional="true" exponent="1" pos="0 0 1.3" specular=".1 .1 .1"/>
|
||||
<geom conaffinity="1" condim="3" material="MatPlane" name="floor" pos="0 0 -0.1" rgba="0.8 0.9 0.8 1" size="40 40 0.1" type="plane"/>
|
||||
<!-- ================= SWIMMER ================= /-->
|
||||
<body name="torso" pos="0 0 0">
|
||||
<geom density="1000" fromto="1.5 0 0 0.5 0 0" size="0.1" type="capsule"/>
|
||||
<joint axis="1 0 0" name="slider1" pos="0 0 0" type="slide"/>
|
||||
<joint axis="0 1 0" name="slider2" pos="0 0 0" type="slide"/>
|
||||
<joint axis="0 0 1" name="rot" pos="0 0 0" type="hinge"/>
|
||||
<body name="mid" pos="0.5 0 0">
|
||||
<geom density="1000" fromto="0 0 0 -1 0 0" size="0.1" type="capsule"/>
|
||||
<joint axis="0 0 1" limited="true" name="rot2" pos="0 0 0" range="-100 100" type="hinge"/>
|
||||
<body name="back" pos="-1 0 0">
|
||||
<geom density="1000" fromto="0 0 0 -1 0 0" size="0.1" type="capsule"/>
|
||||
<joint axis="0 0 1" limited="true" name="rot3" pos="0 0 0" range="-100 100" type="hinge"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
<actuator>
|
||||
<motor ctrllimited="true" ctrlrange="-1 1" gear="150.0" joint="rot2"/>
|
||||
<motor ctrllimited="true" ctrlrange="-1 1" gear="150.0" joint="rot3"/>
|
||||
</actuator>
|
||||
</mujoco>
|
@ -295,6 +295,11 @@ SET(BulletExampleBrowser_SRCS
|
||||
../Importers/ImportURDFDemo/ImportURDFSetup.h
|
||||
../Importers/ImportURDFDemo/URDF2Bullet.h
|
||||
../Importers/ImportURDFDemo/urdf_samples.h
|
||||
../Importers/ImportURDFDemo/urdf_samples.h
|
||||
../Importers/ImportMJCFDemo/BulletMJCFImporter.cpp
|
||||
../Importers/ImportMJCFDemo/BulletMJCFImporter.h
|
||||
../Importers/ImportMJCFDemo/ImportMJCFSetup.cpp
|
||||
../Importers/ImportMJCFDemo/ImportMJCFSetup.h
|
||||
../Importers/ImportBsp/BspConverter.cpp
|
||||
../Importers/ImportBsp/BspLoader.cpp
|
||||
../Importers/ImportBsp/ImportBspExample.cpp
|
||||
|
@ -18,6 +18,7 @@
|
||||
#include "../Importers/ImportSTLDemo/ImportSTLSetup.h"
|
||||
#include "../Importers/ImportURDFDemo/ImportURDFSetup.h"
|
||||
#include "../Importers/ImportSDFDemo/ImportSDFSetup.h"
|
||||
#include "../Importers/ImportMJCFDemo/ImportMJCFSetup.h"
|
||||
#include "../Collision/CollisionTutorialBullet2.h"
|
||||
#include "../GyroscopicDemo/GyroscopicSetup.h"
|
||||
#include "../Constraints/Dof6Spring2Setup.h"
|
||||
@ -231,6 +232,8 @@ static ExampleEntry gDefaultExamples[]=
|
||||
ExampleEntry(1,"URDF (RigidBody)", "Import a URDF file, and create rigid bodies (btRigidBody) connected by constraints.", ImportURDFCreateFunc, 0),
|
||||
ExampleEntry(1,"URDF (MultiBody)", "Import a URDF file and create a single multibody (btMultiBody) with tree hierarchy of links (mobilizers).",
|
||||
ImportURDFCreateFunc, 1),
|
||||
ExampleEntry(1,"MJCF (MultiBody)", "Import a MJCF xml file, create multiple multibodies etc", ImportMJCFCreateFunc),
|
||||
|
||||
ExampleEntry(1,"SDF (MultiBody)", "Import an SDF file, create multiple multibodies etc", ImportSDFCreateFunc),
|
||||
|
||||
ExampleEntry(0,"Vehicles"),
|
||||
|
1098
examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp
Normal file
1098
examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp
Normal file
File diff suppressed because it is too large
Load Diff
78
examples/Importers/ImportMJCFDemo/BulletMJCFImporter.h
Normal file
78
examples/Importers/ImportMJCFDemo/BulletMJCFImporter.h
Normal file
@ -0,0 +1,78 @@
|
||||
#ifndef BULLET_MJCF_IMPORTER_H
|
||||
#define BULLET_MJCF_IMPORTER_H
|
||||
|
||||
#include "../ImportURDFDemo/URDFImporterInterface.h"
|
||||
#include "../ImportURDFDemo/LinkVisualShapesConverter.h"
|
||||
|
||||
|
||||
struct MJCFErrorLogger
|
||||
{
|
||||
virtual void reportError(const char* error)=0;
|
||||
virtual void reportWarning(const char* warning)=0;
|
||||
virtual void printMessage(const char* msg)=0;
|
||||
};
|
||||
|
||||
|
||||
|
||||
class BulletMJCFImporter : public URDFImporterInterface
|
||||
{
|
||||
struct BulletMJCFImporterInternalData* m_data;
|
||||
|
||||
|
||||
public:
|
||||
BulletMJCFImporter(struct GUIHelperInterface* helper);
|
||||
virtual ~BulletMJCFImporter();
|
||||
|
||||
virtual bool parseMJCFString(const char* xmlString, MJCFErrorLogger* logger);
|
||||
|
||||
virtual bool loadMJCF(const char* fileName, MJCFErrorLogger* logger, bool forceFixedBase = false);
|
||||
|
||||
int getNumModels() const;
|
||||
|
||||
void activateModel(int modelIndex);
|
||||
|
||||
virtual bool loadURDF(const char* fileName, bool forceFixedBase = false)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
virtual bool loadSDF(const char* fileName, bool forceFixedBase = false) { return false;}
|
||||
|
||||
virtual const char* getPathPrefix();
|
||||
|
||||
///return >=0 for the root link index, -1 if there is no root link
|
||||
virtual int getRootLinkIndex() const;
|
||||
|
||||
///pure virtual interfaces, precondition is a valid linkIndex (you can assert/terminate if the linkIndex is out of range)
|
||||
virtual std::string getLinkName(int linkIndex) const;
|
||||
|
||||
/// optional method to provide the link color. return true if the color is available and copied into colorRGBA, return false otherwise
|
||||
virtual bool getLinkColor(int linkIndex, btVector4& colorRGBA) const;
|
||||
|
||||
///this API will likely change, don't override it!
|
||||
virtual bool getLinkContactInfo(int linkIndex, URDFLinkContactInfo& contactInfo ) const;
|
||||
|
||||
virtual std::string getJointName(int linkIndex) const;
|
||||
|
||||
//fill mass and inertial data. If inertial data is missing, please initialize mass, inertia to sensitive values, and inertialFrame to identity.
|
||||
virtual void getMassAndInertia(int urdfLinkIndex, btScalar& mass,btVector3& localInertiaDiagonal, btTransform& inertialFrame) const;
|
||||
|
||||
///fill an array of child link indices for this link, btAlignedObjectArray behaves like a std::vector so just use push_back and resize(0) if needed
|
||||
virtual void getLinkChildIndices(int urdfLinkIndex, btAlignedObjectArray<int>& childLinkIndices) const;
|
||||
|
||||
virtual bool getJointInfo(int urdfLinkIndex, btTransform& parent2joint, btTransform& linkTransformInWorld, btVector3& jointAxisInJointSpace, int& jointType, btScalar& jointLowerLimit, btScalar& jointUpperLimit, btScalar& jointDamping, btScalar& jointFriction) const;
|
||||
|
||||
virtual bool getRootTransformInWorld(btTransform& rootTransformInWorld) const;
|
||||
|
||||
virtual int convertLinkVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& inertialFrame) const;
|
||||
|
||||
virtual void convertLinkVisualShapes2(int linkIndex, const char* pathPrefix, const btTransform& inertialFrame, class btCollisionObject* colObj, int objectIndex) const;
|
||||
virtual void setBodyUniqueId(int bodyId);
|
||||
virtual int getBodyUniqueId() const;
|
||||
|
||||
virtual class btCompoundShape* convertLinkCollisionShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame) const ;
|
||||
|
||||
|
||||
};
|
||||
|
||||
#endif //BULLET_MJCF_IMPORTER_H
|
@ -14,6 +14,8 @@
|
||||
#include "../CommonInterfaces/CommonMultiBodyBase.h"
|
||||
|
||||
#include "../ImportURDFDemo/MyMultiBodyCreator.h"
|
||||
#include "BulletMJCFImporter.h"
|
||||
#include "../ImportURDFDemo/URDF2Bullet.h"
|
||||
|
||||
class ImportMJCFSetup : public CommonMultiBodyBase
|
||||
{
|
||||
@ -63,7 +65,7 @@ struct ImportMJCFInternalData
|
||||
}
|
||||
|
||||
|
||||
btScalar m_motorTargetVelocities[MAX_NUM_MOTORS];
|
||||
btScalar m_motorTargetPositions[MAX_NUM_MOTORS];
|
||||
btMultiBodyJointMotor* m_jointMotors [MAX_NUM_MOTORS];
|
||||
btGeneric6DofSpring2Constraint* m_generic6DofJointMotors [MAX_NUM_MOTORS];
|
||||
int m_numMotors;
|
||||
@ -75,19 +77,13 @@ struct ImportMJCFInternalData
|
||||
|
||||
ImportMJCFSetup::ImportMJCFSetup(struct GUIHelperInterface* helper, int option, const char* fileName)
|
||||
:CommonMultiBodyBase(helper),
|
||||
m_grav(0),
|
||||
m_grav(-10),
|
||||
m_upAxis(2)
|
||||
{
|
||||
m_data = new ImportMJCFInternalData;
|
||||
|
||||
if (option==1)
|
||||
{
|
||||
m_useMultiBody = true;
|
||||
} else
|
||||
{
|
||||
m_useMultiBody = false;
|
||||
}
|
||||
|
||||
m_useMultiBody = true;
|
||||
|
||||
static int count = 0;
|
||||
if (fileName)
|
||||
{
|
||||
@ -121,8 +117,13 @@ ImportMJCFSetup::ImportMJCFSetup(struct GUIHelperInterface* helper, int option,
|
||||
|
||||
if (gMCFJFileNameArray.size()==0)
|
||||
{
|
||||
gMCFJFileNameArray.push_back("quadruped/quadruped.mjcf");
|
||||
|
||||
gMCFJFileNameArray.push_back("mjcf/humanoid.xml");
|
||||
gMCFJFileNameArray.push_back("mjcf/hello_mjcf2.xml");
|
||||
gMCFJFileNameArray.push_back("mjcf/capsule.xml");
|
||||
gMCFJFileNameArray.push_back("mjcf/ant.xml");
|
||||
// gMCFJFileNameArray.push_back("mjcf/hopper.xml");
|
||||
// gMCFJFileNameArray.push_back("mjcf/swimmer.xml");
|
||||
// gMCFJFileNameArray.push_back("mjcf/reacher.xml");
|
||||
}
|
||||
|
||||
int numFileNames = gMCFJFileNameArray.size();
|
||||
@ -170,7 +171,21 @@ void ImportMJCFSetup::setFileName(const char* mjcfFileName)
|
||||
}
|
||||
|
||||
|
||||
|
||||
struct MyMJCFLogger : public MJCFErrorLogger
|
||||
{
|
||||
virtual void reportError(const char* error)
|
||||
{
|
||||
b3Error(error);
|
||||
}
|
||||
virtual void reportWarning(const char* warning)
|
||||
{
|
||||
b3Warning(warning);
|
||||
}
|
||||
virtual void printMessage(const char* msg)
|
||||
{
|
||||
b3Printf(msg);
|
||||
}
|
||||
};
|
||||
|
||||
void ImportMJCFSetup::initPhysics()
|
||||
{
|
||||
@ -196,7 +211,132 @@ void ImportMJCFSetup::initPhysics()
|
||||
m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
|
||||
}
|
||||
|
||||
BulletMJCFImporter importer(m_guiHelper);
|
||||
MyMJCFLogger logger;
|
||||
bool result = importer.loadMJCF(m_fileName,&logger);
|
||||
if (result)
|
||||
{
|
||||
btTransform rootTrans;
|
||||
rootTrans.setIdentity();
|
||||
|
||||
for (int m =0; m<importer.getNumModels();m++)
|
||||
{
|
||||
|
||||
importer.activateModel(m);
|
||||
|
||||
btMultiBody* mb = 0;
|
||||
|
||||
|
||||
//todo: move these internal API called inside the 'ConvertURDF2Bullet' call, hidden from the user
|
||||
int rootLinkIndex = importer.getRootLinkIndex();
|
||||
//b3Printf("urdf root link index = %d\n",rootLinkIndex);
|
||||
MyMultiBodyCreator creation(m_guiHelper);
|
||||
|
||||
rootTrans.setIdentity();
|
||||
importer.getRootTransformInWorld(rootTrans);
|
||||
|
||||
ConvertURDF2Bullet(importer,creation, rootTrans,m_dynamicsWorld,m_useMultiBody,importer.getPathPrefix(),CUF_USE_MJCF);
|
||||
|
||||
mb = creation.getBulletMultiBody();
|
||||
if (mb)
|
||||
{
|
||||
printf("first MJCF file converted!\n");
|
||||
std::string* name = new std::string(importer.getLinkName(importer.getRootLinkIndex()));
|
||||
m_nameMemory.push_back(name);
|
||||
#ifdef TEST_MULTIBODY_SERIALIZATION
|
||||
s->registerNameForPointer(name->c_str(),name->c_str());
|
||||
#endif//TEST_MULTIBODY_SERIALIZATION
|
||||
mb->setBaseName(name->c_str());
|
||||
//create motors for each btMultiBody joint
|
||||
int numLinks = mb->getNumLinks();
|
||||
for (int i=0;i<numLinks;i++)
|
||||
{
|
||||
int mbLinkIndex = i;
|
||||
int urdfLinkIndex = creation.m_mb2urdfLink[mbLinkIndex];
|
||||
|
||||
std::string* jointName = new std::string(importer.getJointName(urdfLinkIndex));
|
||||
std::string* linkName = new std::string(importer.getLinkName(urdfLinkIndex).c_str());
|
||||
#ifdef TEST_MULTIBODY_SERIALIZATION
|
||||
s->registerNameForPointer(jointName->c_str(),jointName->c_str());
|
||||
s->registerNameForPointer(linkName->c_str(),linkName->c_str());
|
||||
#endif//TEST_MULTIBODY_SERIALIZATION
|
||||
m_nameMemory.push_back(jointName);
|
||||
m_nameMemory.push_back(linkName);
|
||||
|
||||
mb->getLink(i).m_linkName = linkName->c_str();
|
||||
mb->getLink(i).m_jointName = jointName->c_str();
|
||||
|
||||
if (mb->getLink(mbLinkIndex).m_jointType==btMultibodyLink::eRevolute
|
||||
||mb->getLink(mbLinkIndex).m_jointType==btMultibodyLink::ePrismatic
|
||||
)
|
||||
{
|
||||
if (m_data->m_numMotors<MAX_NUM_MOTORS)
|
||||
{
|
||||
|
||||
char motorName[1024];
|
||||
sprintf(motorName,"%s q ", jointName->c_str());
|
||||
btScalar* motorPos = &m_data->m_motorTargetPositions[m_data->m_numMotors];
|
||||
*motorPos = 0.f;
|
||||
SliderParams slider(motorName,motorPos);
|
||||
slider.m_minVal=-4;
|
||||
slider.m_maxVal=4;
|
||||
slider.m_clampToIntegers = false;
|
||||
slider.m_clampToNotches = false;
|
||||
m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
|
||||
float maxMotorImpulse = 5.f;
|
||||
btMultiBodyJointMotor* motor = new btMultiBodyJointMotor(mb,mbLinkIndex,0,0,maxMotorImpulse);
|
||||
motor->setErp(0.1);
|
||||
//motor->setMaxAppliedImpulse(0);
|
||||
m_data->m_jointMotors[m_data->m_numMotors]=motor;
|
||||
m_dynamicsWorld->addMultiBodyConstraint(motor);
|
||||
m_data->m_numMotors++;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
} else
|
||||
{
|
||||
if (1)
|
||||
{
|
||||
//create motors for each generic joint
|
||||
int num6Dof = creation.getNum6DofConstraints();
|
||||
for (int i=0;i<num6Dof;i++)
|
||||
{
|
||||
btGeneric6DofSpring2Constraint* c = creation.get6DofConstraint(i);
|
||||
if (c->getUserConstraintPtr())
|
||||
{
|
||||
GenericConstraintUserInfo* jointInfo = (GenericConstraintUserInfo*)c->getUserConstraintPtr();
|
||||
if ((jointInfo->m_urdfJointType ==URDFRevoluteJoint) ||
|
||||
(jointInfo->m_urdfJointType ==URDFPrismaticJoint) ||
|
||||
(jointInfo->m_urdfJointType ==URDFContinuousJoint))
|
||||
{
|
||||
int urdfLinkIndex = jointInfo->m_urdfIndex;
|
||||
std::string jointName = importer.getJointName(urdfLinkIndex);
|
||||
char motorName[1024];
|
||||
sprintf(motorName,"%s q'", jointName.c_str());
|
||||
btScalar* motorVel = &m_data->m_motorTargetPositions[m_data->m_numMotors];
|
||||
|
||||
*motorVel = 0.f;
|
||||
SliderParams slider(motorName,motorVel);
|
||||
slider.m_minVal=-4;
|
||||
slider.m_maxVal=4;
|
||||
m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
|
||||
m_data->m_generic6DofJointMotors[m_data->m_numMotors]=c;
|
||||
bool motorOn = true;
|
||||
c->enableMotor(jointInfo->m_jointAxisIndex,motorOn);
|
||||
c->setMaxMotorForce(jointInfo->m_jointAxisIndex,10000);
|
||||
c->setTargetVelocity(jointInfo->m_jointAxisIndex,0);
|
||||
|
||||
m_data->m_numMotors++;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
@ -206,7 +346,7 @@ void ImportMJCFSetup::stepSimulation(float deltaTime)
|
||||
{
|
||||
if (m_dynamicsWorld)
|
||||
{
|
||||
btVector3 gravity(0, 0, 0);
|
||||
btVector3 gravity(0, 0, -10);
|
||||
gravity[m_upAxis] = m_grav;
|
||||
m_dynamicsWorld->setGravity(gravity);
|
||||
|
||||
@ -214,13 +354,12 @@ void ImportMJCFSetup::stepSimulation(float deltaTime)
|
||||
{
|
||||
if (m_data->m_jointMotors[i])
|
||||
{
|
||||
m_data->m_jointMotors[i]->setVelocityTarget(m_data->m_motorTargetVelocities[i]);
|
||||
m_data->m_jointMotors[i]->setPositionTarget(m_data->m_motorTargetPositions[i]);
|
||||
}
|
||||
if (m_data->m_generic6DofJointMotors[i])
|
||||
{
|
||||
GenericConstraintUserInfo* jointInfo = (GenericConstraintUserInfo*)m_data->m_generic6DofJointMotors[i]->getUserConstraintPtr();
|
||||
m_data->m_generic6DofJointMotors[i]->setTargetVelocity(jointInfo->m_jointAxisIndex,m_data->m_motorTargetVelocities[i]);
|
||||
//jointInfo->
|
||||
m_data->m_generic6DofJointMotors[i]->setTargetVelocity(jointInfo->m_jointAxisIndex,m_data->m_motorTargetPositions[i]);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -89,7 +89,7 @@ struct ImportUrdfInternalData
|
||||
|
||||
ImportUrdfSetup::ImportUrdfSetup(struct GUIHelperInterface* helper, int option, const char* fileName)
|
||||
:CommonMultiBodyBase(helper),
|
||||
m_grav(0),
|
||||
m_grav(-10),
|
||||
m_upAxis(2)
|
||||
{
|
||||
m_data = new ImportUrdfInternalData;
|
||||
@ -135,7 +135,7 @@ ImportUrdfSetup::ImportUrdfSetup(struct GUIHelperInterface* helper, int option,
|
||||
|
||||
if (gFileNameArray.size()==0)
|
||||
{
|
||||
gFileNameArray.push_back("quadruped/quadruped.urdf");
|
||||
gFileNameArray.push_back("r2d2.urdf");
|
||||
|
||||
}
|
||||
|
||||
|
@ -237,7 +237,13 @@ void ConvertURDF2BulletInternal(
|
||||
}
|
||||
else
|
||||
{
|
||||
linkTransformInWorldSpace =parentTransformInWorldSpace*parent2joint;
|
||||
if (flags & CUF_USE_MJCF)
|
||||
{
|
||||
linkTransformInWorldSpace =parentTransformInWorldSpace*linkTransformInWorldSpace;
|
||||
} else
|
||||
{
|
||||
linkTransformInWorldSpace =parentTransformInWorldSpace*parent2joint;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
@ -17,7 +17,8 @@ class MultiBodyCreationInterface;
|
||||
enum ConvertURDFFlags {
|
||||
CUF_USE_SDF = 1,
|
||||
// Use inertia values in URDF instead of recomputing them from collision shape.
|
||||
CUF_USE_URDF_INERTIA = 2
|
||||
CUF_USE_URDF_INERTIA = 2,
|
||||
CUF_USE_MJCF = 4,
|
||||
};
|
||||
|
||||
void ConvertURDF2Bullet(const URDFImporterInterface& u2b,
|
||||
|
@ -44,6 +44,7 @@ enum UrdfGeomTypes
|
||||
URDF_GEOM_CYLINDER,
|
||||
URDF_GEOM_MESH,
|
||||
URDF_GEOM_PLANE,
|
||||
URDF_GEOM_CAPSULE//non-standard URDF?
|
||||
|
||||
};
|
||||
|
||||
@ -56,6 +57,10 @@ struct UrdfGeometry
|
||||
|
||||
btVector3 m_boxSize;
|
||||
|
||||
double m_capsuleRadius;
|
||||
btVector3 m_capsuleFrom;
|
||||
btVector3 m_capsuleTo;
|
||||
|
||||
double m_cylinderRadius;
|
||||
double m_cylinderLength;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user