Skip to content

Commit

Permalink
Merge pull request #14 from ctu-mrs/balloons
Browse files Browse the repository at this point in the history
added balloons and balls to the simulation
  • Loading branch information
WingRS authored Apr 3, 2023
2 parents 13c56ea + db1ac03 commit 60c2a66
Show file tree
Hide file tree
Showing 33 changed files with 763 additions and 0 deletions.
Binary file added models/ball_green/materials/textures/green.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
16 changes: 16 additions & 0 deletions models/ball_green/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
<?xml version="1.0"?>

<model>
<name>Ball (green)</name>
<version>1.0</version>
<sdf version='1.5'>model.sdf</sdf>

<author>
<name>Matouš Vrba</name>
<email>[email protected]</email>
</author>

<description>
A simple model of a spherical ball with a green texture
</description>
</model>
67 changes: 67 additions & 0 deletions models/ball_green/model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
<?xml version="1.0" ?>
<sdf version="1.5">
<model name="ball_green">
<static>0</static>
<link name="link">
<pose>0 0 0.1 0 0 0</pose>
<inertial>
<mass>0.3</mass>
<inertia>
<ixx>0.08611666666666669</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.08611666666666669</iyy>
<iyz>0</iyz>
<izz>0.08611666666666669</izz>
</inertia>
</inertial>

<collision name="collision_ball">
<pose>0 0 2.0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.25</radius>
</sphere>
</geometry>
<surface>
<contact>
<poissons_ratio>0.347</poissons_ratio>
<elastic_modulus>8.8e+09</elastic_modulus>
<ode>
<kp>100000</kp>
<kd>100</kd>
<max_vel>100.0</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
<friction>
<torsional>
<coefficient>1.0</coefficient>
<use_patch_radius>0</use_patch_radius>
<surface_radius>0.01</surface_radius>
</torsional>
</friction>
</surface>
</collision>

<visual name="ball">
<pose>0 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.25</radius>
</sphere>
</geometry>
<material>
<script>
<uri>model://ball_green/scripts</uri>
<uri>model://ball_green/materials/textures</uri>
<name>BallGreen/ball</name>
</script>
</material>
</visual>

</link>
</model>
</sdf>


19 changes: 19 additions & 0 deletions models/ball_green/scripts/material.material
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
material BallGreen/Ball
{
technique
{
pass
{
ambient 0.5 0.5 0.5 1.0
diffuse 1.0 1.0 1.0 1.0
specular 0.0 0.0 0.0 1.0 0.5

texture_unit
{
texture green.png
filtering bilienear
scale 1.0 1.0
}
}
}
}
Binary file added models/ball_orange/materials/textures/orange.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
16 changes: 16 additions & 0 deletions models/ball_orange/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
<?xml version="1.0"?>

<model>
<name>Ball (orange)</name>
<version>1.0</version>
<sdf version='1.5'>model.sdf</sdf>

<author>
<name>Matouš Vrba</name>
<email>[email protected]</email>
</author>

<description>
A simple model of a spherical ball with a orange texture
</description>
</model>
67 changes: 67 additions & 0 deletions models/ball_orange/model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
<?xml version="1.0" ?>
<sdf version="1.5">
<model name="ball_orange">
<static>0</static>
<link name="link">
<pose>0 0 0.1 0 0 0</pose>
<inertial>
<mass>0.3</mass>
<inertia>
<ixx>0.08611666666666669</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.08611666666666669</iyy>
<iyz>0</iyz>
<izz>0.08611666666666669</izz>
</inertia>
</inertial>

<collision name="collision_ball">
<pose>0 0 2.0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.25</radius>
</sphere>
</geometry>
<surface>
<contact>
<poissons_ratio>0.347</poissons_ratio>
<elastic_modulus>8.8e+09</elastic_modulus>
<ode>
<kp>100000</kp>
<kd>100</kd>
<max_vel>100.0</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
<friction>
<torsional>
<coefficient>1.0</coefficient>
<use_patch_radius>0</use_patch_radius>
<surface_radius>0.01</surface_radius>
</torsional>
</friction>
</surface>
</collision>

<visual name="ball">
<pose>0 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.25</radius>
</sphere>
</geometry>
<material>
<script>
<uri>model://ball_orange/scripts</uri>
<uri>model://ball_orange/materials/textures</uri>
<name>BallOrange/ball</name>
</script>
</material>
</visual>

</link>
</model>
</sdf>


19 changes: 19 additions & 0 deletions models/ball_orange/scripts/material.material
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
material BallOrange/Ball
{
technique
{
pass
{
ambient 0.5 0.5 0.5 1.0
diffuse 1.0 1.0 1.0 1.0
specular 0.0 0.0 0.0 1.0 0.5

texture_unit
{
texture orange.png
filtering bilienear
scale 1.0 1.0
}
}
}
}
Binary file added models/ball_red/materials/textures/red.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
16 changes: 16 additions & 0 deletions models/ball_red/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
<?xml version="1.0"?>

<model>
<name>Ball (red)</name>
<version>1.0</version>
<sdf version='1.5'>model.sdf</sdf>

<author>
<name>Matouš Vrba</name>
<email>[email protected]</email>
</author>

<description>
A simple model of a spherical ball with a red texture
</description>
</model>
67 changes: 67 additions & 0 deletions models/ball_red/model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
<?xml version="1.0" ?>
<sdf version="1.5">
<model name="ball_red">
<static>0</static>
<link name="link">
<pose>0 0 0.1 0 0 0</pose>
<inertial>
<mass>0.3</mass>
<inertia>
<ixx>0.08611666666666669</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.08611666666666669</iyy>
<iyz>0</iyz>
<izz>0.08611666666666669</izz>
</inertia>
</inertial>

<collision name="collision_ball">
<pose>0 0 2.0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.25</radius>
</sphere>
</geometry>
<surface>
<contact>
<poissons_ratio>0.347</poissons_ratio>
<elastic_modulus>8.8e+09</elastic_modulus>
<ode>
<kp>100000</kp>
<kd>100</kd>
<max_vel>100.0</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
<friction>
<torsional>
<coefficient>1.0</coefficient>
<use_patch_radius>0</use_patch_radius>
<surface_radius>0.01</surface_radius>
</torsional>
</friction>
</surface>
</collision>

<visual name="ball">
<pose>0 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.25</radius>
</sphere>
</geometry>
<material>
<script>
<uri>model://ball_red/scripts</uri>
<uri>model://ball_red/materials/textures</uri>
<name>BallRed/ball</name>
</script>
</material>
</visual>

</link>
</model>
</sdf>


19 changes: 19 additions & 0 deletions models/ball_red/scripts/material.material
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
material BallRed/Ball
{
technique
{
pass
{
ambient 0.5 0.5 0.5 1.0
diffuse 1.0 1.0 1.0 1.0
specular 0.0 0.0 0.0 1.0 0.5

texture_unit
{
texture red.png
filtering bilienear
scale 1.0 1.0
}
}
}
}
Binary file added models/balloon_green/materials/textures/green.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added models/balloon_green/meshes/balonek.stl
Binary file not shown.
16 changes: 16 additions & 0 deletions models/balloon_green/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
<?xml version="1.0"?>

<model>
<name>Balloon (green)</name>
<version>1.0</version>
<sdf version='1.5'>model.sdf</sdf>

<author>
<name>Matouš Vrba</name>
<email>[email protected]</email>
</author>

<description>
A simple model of a spherical balloon with a green texture
</description>
</model>
67 changes: 67 additions & 0 deletions models/balloon_green/model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
<?xml version="1.0" ?>
<sdf version="1.5">
<model name="balloon_green">
<static>0</static>
<link name="link">
<pose>0 0 0.1 0 0 0</pose>
<inertial>
<mass>0.3</mass>
<inertia>
<ixx>0.08611666666666669</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.08611666666666669</iyy>
<iyz>0</iyz>
<izz>0.08611666666666669</izz>
</inertia>
</inertial>

<collision name="collision_balloon">
<pose>0 0 2.0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://balloon_green/meshes/balonek.stl</uri>
</mesh>
</geometry>
<surface>
<contact>
<poissons_ratio>0.347</poissons_ratio>
<elastic_modulus>8.8e+09</elastic_modulus>
<ode>
<kp>100000</kp>
<kd>100</kd>
<max_vel>100.0</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
<friction>
<torsional>
<coefficient>1.0</coefficient>
<use_patch_radius>0</use_patch_radius>
<surface_radius>0.01</surface_radius>
</torsional>
</friction>
</surface>
</collision>

<visual name="balloon">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://balloon_green/meshes/balonek.stl</uri>
</mesh>
</geometry>
<material>
<script>
<uri>model://balloon_green/scripts</uri>
<uri>model://balloon_green/materials/textures</uri>
<name>BalloonGreen/Balloon</name>
</script>
</material>
</visual>

</link>
</model>
</sdf>


Loading

0 comments on commit 60c2a66

Please sign in to comment.