Convert ode to bullet in SDF?
I have a model file for ode engine. If I want to run this model in bullet engine, how do I modify this model file. Which parameters should I modify?
Following is this model file:
<model name="my_car">
<static>false</static>
<link name='chassis'>
<pose>0 0 0.02575 0 0 0</pose>
<inertial>
<pose>-0.015 0 -0.015 0 0 0</pose>
<mass>1.0</mass>
<inertia>
<ixx>9.0e-4</ixx>
<iyy>1.3e-3</iyy>
<izz>1.1e-3</izz>
</inertia>
</inertial>
<velocity_decay>
<linear>0</linear>
<angular>0.1</angular>
</velocity_decay>
<collision name='body_collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<box>
<size>.075 .057 .03</size>
</box>
</geometry>
<surface>
<bounce>
<restitution_coefficient> 0.5 </restitution_coefficient>
<threshold> 0 </threshold>
</bounce>
<friction>
<ode>
<mu> 0.1 </mu>
</ode>
</friction>
</surface>
</collision>
<visual name='body_visual'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<box>
<size>.075 .057 .045</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Blue</name>
</script>
</material>
</visual>
<collision name='Fwheel_collision'>
<pose>.03 0 -0.0225 0 0 0</pose>
<geometry>
<sphere>
<radius>0.0015</radius>
</sphere>
</geometry>
<surface>
<bounce>
<restitution_coefficient> 0 </restitution_coefficient>
<threshold> 100000 </threshold>
</bounce>
<friction>
<ode>
<mu> 0 </mu>
</ode>
</friction>
</surface>
</collision>
<visual name='Fwheel_visual'>
<pose>0.03 0 -0.0225 0 0 0</pose>
<geometry>
<sphere>
<radius>0.0015</radius>
</sphere>
</geometry>
</visual>
<collision name='Bwheel_collision'>
<pose>-0.03 0 -0.0225 0 0 0</pose>
<geometry>
<sphere>
<radius>0.0015</radius>
</sphere>
</geometry>
<surface>
<bounce>
<restitution_coefficient> 0 </restitution_coefficient>
<threshold> 100000 </threshold>
</bounce>
<friction>
<ode>
<mu> 0 </mu>
</ode>
</friction>
</surface>
</collision>
<visual name='Bwheel_visual'>
<pose>-0.03 0 -0.0225 0 0 0</pose>
<geometry>
<sphere>
<radius>0.0015</radius>
</sphere>
</geometry>
</visual>
</link>
<link name="left_wheel">
<pose>0 0.0335 .02 1.570796327 0 0</pose>
<inertial>
<mass>0.03</mass>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>6.0e-5</ixx><!-- 3.16e-6 3.16e-6 6.0e-6 -->
<iyy>6.0e-5</iyy>
<izz>6.0e-5</izz>
</inertia>
</inertial>
<collision name="collision">
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<radius>.02</radius>
<length>.008</length>
</cylinder>
</geometry>
<surface>
<bounce>
<restitution_coefficient> 0 </restitution_coefficient>
<threshold> 100000 </threshold>
</bounce>
<friction>
<ode>
<mu> 1.0 </mu>
<mu2> 1.0 </mu2>
<fdir1>1 0 0</fdir1>
<slip1>0.0</slip1>
<slip2>0.1</slip2> <!---->
</ode>
</friction>
</surface>
</collision>
<visual name="visual">
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<radius>.02</radius>
<length>.008</length>
</cylinder>
</geometry>
</visual>
<sensor name="left_wheel_sensor" type="imu">
</sensor>
</link>
<link name="right_wheel">
<pose>0 -0.0335 .02 1.570796327 0 0</pose>
<inertial>
<mass>0.03</mass>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>6.0e-5</ixx><!-- 3.16e-6 3.16e-6 6.0e-6 -->
<iyy>6.0e-5</iyy>
<izz>6.0e-5</izz>
</inertia>
</inertial>
<collision name="collision">
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<radius>.02</radius>
<length>.008</length>
</cylinder>
</geometry>
<surface>
<bounce>
<restitution_coefficient> 0 </restitution_coefficient>
<threshold> 100000 </threshold>
</bounce>
<friction>
<ode>
<mu> 1.0 </mu>
<mu2> 1.0 </mu2>
<fdir1>1 0 0</fdir1>
<slip1>0.0</slip1>
<slip2>0.1</slip2> <!---->
</ode>
</friction>
</surface>
</collision>
<visual name="visual">
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<radius>.02</radius>
<length>.008</length>
</cylinder>
</geometry>
</visual>
<sensor name="right_wheel_sensor" type="imu">
</sensor>
</link>
<joint type="revolute" name="left_wheel_hinge">
<pose>0 0 0 0 0 0</pose>
<child>left_wheel</child>
<parent>chassis</parent>
<axis>
<xyz>0 1 0</xyz>
<dynamics>
<damping>0.02</damping>
<friction>0</friction>
</dynamics>
</axis>
<physics>
<ode>
<limit>
<cfm>0.5</cfm>
<erp>0.3</erp>
</limit>
</ode>
</physics>
</joint>
<joint type="revolute" name="right_wheel_hinge">
<pose>0 0 0 0 0 0</pose>
<child>right_wheel</child>
<parent>chassis</parent>
<axis>
<xyz>0 1 0</xyz>
<dynamics>
<damping>0.02</damping>
<friction>0</friction>
</dynamics>
</axis>
<physics>
<ode>
<limit>
<cfm>0.5</cfm>
<erp>0.3</erp>
</limit>
</ode>
</physics>
</joint>
Asked by Sam on 2014-01-22 09:43:58 UTC
Answers
In general have a look at the sdf specification (for example: sdf 1.4 )
In general you have to rewrite all <ode>
blocks by adding a corresponding <bullet>
block.
I don't think that having both (ode and bullet blocks will make problem but i have never tried )
For Example your first ode tag
<ode>
<mu> 0.1 </mu>
</ode>
will change to
<bullet>
<friction> 0.1 </friction>
</bullet>
But some of your settings might not be available with bullet. For Example there seems to be no joint/physics/bullet
tag in SDF...
When starting gazebo don't forget to specify bullet as pysic engine
gazebo -e bullet
Asked by evilBiber on 2014-01-22 10:21:07 UTC
Comments