Skip to content

Commit

Permalink
Add test friction values mu and mu2
Browse files Browse the repository at this point in the history
Signed-off-by: Jorge Perez <jjperez@ekumenlabs.com>
  • Loading branch information
Blast545 committed Mar 3, 2021
1 parent c583765 commit 4cf6b4e
Show file tree
Hide file tree
Showing 3 changed files with 487 additions and 1 deletion.
2 changes: 1 addition & 1 deletion bullet/src/SDFFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -213,7 +213,7 @@ Identity SDFFeatures::ConstructSdfCollision(
// shape->setMargin(btScalar(0.0001));
body->setFriction(1);
// body->setRollingFriction(0.25);
body->setAnisotropicFriction(btVector3(mu2, mu, 0),
body->setAnisotropicFriction(btVector3(mu2, mu, 1),
btCollisionObject::CF_ANISOTROPIC_FRICTION);

dynamic_cast<btCompoundShape *>(body->getCollisionShape())
Expand Down
259 changes: 259 additions & 0 deletions bullet/worlds/test_friction_mu.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,259 @@
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="shapes">
<physics name="1ms" type="ignored">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
<plugin
filename="ignition-gazebo-physics-system"
name="ignition::gazebo::systems::Physics">
</plugin>
<plugin
filename="ignition-gazebo-user-commands-system"
name="ignition::gazebo::systems::UserCommands">
</plugin>
<plugin
filename="ignition-gazebo-scene-broadcaster-system"
name="ignition::gazebo::systems::SceneBroadcaster">
</plugin>

<scene>
<ambient>1.0 1.0 1.0</ambient>
<background>0.8 0.8 0.8</background>
</scene>

<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>

<model name="tilted_box_fixed">
<pose>0 5.4 2 0.35 0 0</pose>
<static>true</static>
<link name="tilted_box_link">
<collision name="collision">
<geometry>
<box>
<size>15 15 0.1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>15 15 0.1</size>
</box>
</geometry>
<material>
<ambient>0. 0.8 0.8 1</ambient>
<diffuse>0. 0.8 0.8 1</diffuse>
<specular>0. 0.8 0.8 1</specular>
</material>
</visual>
</link>
</model>

<model name="tilted_box_fixed_2">
<pose>-7 -10 0 0 0.35 0</pose>
<static>true</static>
<link name="tilted_box_link">
<collision name="collision">
<geometry>
<box>
<size>30 30 0.1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>30 30 0.1</size>
</box>
</geometry>
<material>
<ambient>0.8 0.8 0. 1</ambient>
<diffuse>0.8 0.8 0. 1</diffuse>
<specular>0.8 0.8 0. 1</specular>
</material>
</visual>
</link>
</model>

<model name="ground_plane">
<pose>0 0 0 0 0 0</pose>
<static>true</static>
<link name="ground_plane_link">
<collision name="collision">
<geometry>
<box>
<size>12 12 0.1</size>
</box>
<!-- <plane> -->
<!-- <normal>0 0 1</normal> -->
<!-- </plane> -->
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>12 12 0.1</size>
</box>
<!-- <normal>0 0 1</normal> -->
<!-- <size>100 100</size> -->
</geometry>
<material>
<ambient>0.8 0. 0.8 1</ambient>
<diffuse>0.8 0. 0.8 1</diffuse>
<specular>0.8 0. 0.8 1</specular>
</material>
</visual>
</link>
</model>

<model name="green_box">
<pose>0 5 2.7 0 0 0</pose>
<link name="box_link">
<inertial>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<collision name="box_collision">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0.5</mu2>
</ode>
</friction>
</surface>
</collision>

<visual name="box_visual">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
<material>
<ambient>0 1 0 1</ambient>
<diffuse>0 1 0 1</diffuse>
<specular>0 1 0 1</specular>
</material>
</visual>
</link>
</model>

<model name="red_box">
<pose>-1.5 5 2.7 0 0 0</pose>
<link name="box_link">
<inertial>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<collision name="box_collision">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
<surface>
<friction>
<ode>
<mu>0.5</mu>
<mu2>0</mu2>
</ode>
</friction>
</surface>
</collision>

<visual name="box_visual">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>1 0 0 1</diffuse>
<specular>1 0 0 1</specular>
</material>
</visual>
</link>
</model>

<model name="blue_box">
<pose>1.5 5 2.7 0 0 0</pose>
<link name="box_link">
<inertial>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<collision name="box_collision">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
<surface>
<friction>
<ode>
<mu>0.3</mu>
<mu2>0.3</mu2>
</ode>
</friction>
</surface>
</collision>

<visual name="box_visual">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
<material>
<ambient>0 0 1 1</ambient>
<diffuse>0 0 1 1</diffuse>
<specular>0 0 1 1</specular>
</material>
</visual>
</link>
</model>

</world>
</sdf>
Loading

0 comments on commit 4cf6b4e

Please sign in to comment.