-
Notifications
You must be signed in to change notification settings - Fork 277
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Added tutorial for Automatic Inertia Calculator (#2119)
Signed-off-by: Jasmeet Singh <jasmeet0915@gmail.com>
- Loading branch information
1 parent
509d01a
commit 4d4b680
Showing
7 changed files
with
721 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,367 @@ | ||
<?xml version="1.0" ?> | ||
<!-- | ||
Demo of Automatic Inertia Calculations using a pendulum setup | ||
--> | ||
<sdf version="1.11"> | ||
<world name="auto_inertia_pendulum"> | ||
<physics name="1ms" type="ignored"> | ||
<max_step_size>0.001</max_step_size> | ||
<real_time_factor>1.0</real_time_factor> | ||
</physics> | ||
<plugin | ||
filename="gz-sim-physics-system" | ||
name="gz::sim::systems::Physics"> | ||
</plugin> | ||
<plugin | ||
filename="gz-sim-user-commands-system" | ||
name="gz::sim::systems::UserCommands"> | ||
</plugin> | ||
<plugin | ||
filename="gz-sim-scene-broadcaster-system" | ||
name="gz::sim::systems::SceneBroadcaster"> | ||
</plugin> | ||
|
||
<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.2 0.2 0.2 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="ground_plane"> | ||
<static>true</static> | ||
<link name="link"> | ||
<collision name="collision"> | ||
<geometry> | ||
<plane> | ||
<normal>0 0 1</normal> | ||
<size>100 100</size> | ||
</plane> | ||
</geometry> | ||
</collision> | ||
<visual name="visual"> | ||
<geometry> | ||
<plane> | ||
<normal>0 0 1</normal> | ||
<size>100 100</size> | ||
</plane> | ||
</geometry> | ||
<material> | ||
<ambient>0.8 0.8 0.8 1</ambient> | ||
<diffuse>0.8 0.8 0.8 1</diffuse> | ||
<specular>0.8 0.8 0.8 1</specular> | ||
</material> | ||
</visual> | ||
</link> | ||
</model> | ||
|
||
<model name="pendulum"> | ||
<link name="base"> | ||
<inertial> | ||
<pose>-0.188749 0 0.75813399999999997 -0.13567899999999999 0 1.5708</pose> | ||
<mass>256.42500000000001</mass> | ||
<inertia> | ||
<ixx>154.202</ixx> | ||
<ixy>0</ixy> | ||
<ixz>0</ixz> | ||
<iyy>152.286</iyy> | ||
<iyz>0</iyz> | ||
<izz>28.8249</izz> | ||
</inertia> | ||
</inertial> | ||
<visual name="vis_plate_on_ground"> | ||
<pose>0 0 0.01 0 0 0</pose> | ||
<geometry> | ||
<cylinder> | ||
<radius>0.8</radius> | ||
<length>0.02</length> | ||
</cylinder> | ||
</geometry> | ||
<material> | ||
<ambient>0.8 0.8 0.8 1</ambient> | ||
<diffuse>0.8 0.8 0.8 1</diffuse> | ||
<specular>0.8 0.8 0.8 1</specular> | ||
</material> | ||
</visual> | ||
<visual name="vis_pole"> | ||
<pose>-0.275 0 1.1 0 0 0</pose> | ||
<geometry> | ||
<box> | ||
<size>0.2 0.2 2.2</size> | ||
</box> | ||
</geometry> | ||
<material> | ||
<ambient>0.8 0.8 0.8 1</ambient> | ||
<diffuse>0.8 0.8 0.8 1</diffuse> | ||
<specular>0.8 0.8 0.8 1</specular> | ||
</material> | ||
</visual> | ||
<collision name="col_plate_on_ground"> | ||
<pose>0 0 0.01 0 0 0</pose> | ||
<geometry> | ||
<cylinder> | ||
<radius>0.8</radius> | ||
<length>0.02</length> | ||
</cylinder> | ||
</geometry> | ||
</collision> | ||
<collision name="col_pole"> | ||
<pose>-0.275 0 1.1 0 0 0</pose> | ||
<geometry> | ||
<box> | ||
<size>0.2 0.2 2.2</size> | ||
</box> | ||
</geometry> | ||
</collision> | ||
</link> | ||
|
||
<!-- upper link, length 1, IC -90 degrees --> | ||
<link name="upper_link"> | ||
<pose>0 0 2.1 -1.5708 0 0</pose> | ||
<self_collide>0</self_collide> | ||
<inertial auto="true" /> | ||
<visual name="vis_upper_joint"> | ||
<pose>-0.05 0 0 0 1.5708 0</pose> | ||
<geometry> | ||
<cylinder> | ||
<radius>0.1</radius> | ||
<length>0.3</length> | ||
</cylinder> | ||
</geometry> | ||
<material> | ||
<ambient>0.8 0.8 0.8 1</ambient> | ||
<diffuse>0.8 0.8 0.8 1</diffuse> | ||
<specular>0.8 0.8 0.8 1</specular> | ||
</material> | ||
</visual> | ||
<visual name="vis_bob"> | ||
<pose>0 0 1.0 0 1.5708 0</pose> | ||
<geometry> | ||
<cylinder> | ||
<radius>0.1</radius> | ||
<length>0.2</length> | ||
</cylinder> | ||
</geometry> | ||
<material> | ||
<ambient>0.8 0.8 0.8 1</ambient> | ||
<diffuse>0.8 0.8 0.8 1</diffuse> | ||
<specular>0.8 0.8 0.8 1</specular> | ||
</material> | ||
</visual> | ||
<visual name="vis_cylinder"> | ||
<pose>0 0 0.5 0 0 0</pose> | ||
<geometry> | ||
<cylinder> | ||
<radius>0.1</radius> | ||
<length>0.9</length> | ||
</cylinder> | ||
</geometry> | ||
<material> | ||
<ambient>0.8 0.8 0.8 1</ambient> | ||
<diffuse>0.8 0.8 0.8 1</diffuse> | ||
<specular>0.8 0.8 0.8 1</specular> | ||
</material> | ||
</visual> | ||
<collision name="col_upper_joint"> | ||
<density>8000</density> | ||
<pose>-0.05 0 0 0 1.5708 0</pose> | ||
<geometry> | ||
<cylinder> | ||
<radius>0.1</radius> | ||
<length>0.3</length> | ||
</cylinder> | ||
</geometry> | ||
</collision> | ||
<collision name="col_bob"> | ||
<density>1000</density> | ||
<pose>0 0 1.0 0 1.5708 0</pose> | ||
<geometry> | ||
<cylinder> | ||
<radius>0.1</radius> | ||
<length>0.3</length> | ||
</cylinder> | ||
</geometry> | ||
</collision> | ||
<collision name="col_cylinder"> | ||
<density>1000</density> | ||
<pose>0 0 0.5 0 0 0</pose> | ||
<geometry> | ||
<cylinder> | ||
<radius>0.1</radius> | ||
<length>0.9</length> | ||
</cylinder> | ||
</geometry> | ||
</collision> | ||
</link> | ||
|
||
<!-- pin joint for upper link, at origin of upper link --> | ||
<joint name="upper_joint" type="revolute"> | ||
<parent>base</parent> | ||
<child>upper_link</child> | ||
<axis> | ||
<xyz>1.0 0 0</xyz> | ||
</axis> | ||
</joint> | ||
</model> | ||
|
||
<model name="pendulum2"> | ||
<pose>0 3 0 0 0 0</pose> | ||
<link name="base"> | ||
<inertial> | ||
<pose>-0.188749 0 0.75813399999999997 -0.13567899999999999 0 1.5708</pose> | ||
<mass>256.42500000000001</mass> | ||
<inertia> | ||
<ixx>154.202</ixx> | ||
<ixy>0</ixy> | ||
<ixz>0</ixz> | ||
<iyy>152.286</iyy> | ||
<iyz>0</iyz> | ||
<izz>28.8249</izz> | ||
</inertia> | ||
</inertial> | ||
<visual name="vis_plate_on_ground"> | ||
<pose>0 0 0.01 0 0 0</pose> | ||
<geometry> | ||
<cylinder> | ||
<radius>0.8</radius> | ||
<length>0.02</length> | ||
</cylinder> | ||
</geometry> | ||
<material> | ||
<ambient>0.8 0.8 0.8 1</ambient> | ||
<diffuse>0.8 0.8 0.8 1</diffuse> | ||
<specular>0.8 0.8 0.8 1</specular> | ||
</material> | ||
</visual> | ||
<visual name="vis_pole"> | ||
<pose>-0.275 0 1.1 0 0 0</pose> | ||
<geometry> | ||
<box> | ||
<size>0.2 0.2 2.2</size> | ||
</box> | ||
</geometry> | ||
<material> | ||
<ambient>0.8 0.8 0.8 1</ambient> | ||
<diffuse>0.8 0.8 0.8 1</diffuse> | ||
<specular>0.8 0.8 0.8 1</specular> | ||
</material> | ||
</visual> | ||
<collision name="col_plate_on_ground"> | ||
<pose>0 0 0.01 0 0 0</pose> | ||
<geometry> | ||
<cylinder> | ||
<radius>0.8</radius> | ||
<length>0.02</length> | ||
</cylinder> | ||
</geometry> | ||
</collision> | ||
<collision name="col_pole"> | ||
<pose>-0.275 0 1.1 0 0 0</pose> | ||
<geometry> | ||
<box> | ||
<size>0.2 0.2 2.2</size> | ||
</box> | ||
</geometry> | ||
</collision> | ||
</link> | ||
|
||
<!-- upper link, length 1, IC -90 degrees --> | ||
<link name="upper_link"> | ||
<pose>0 0 2.1 -1.5708 0 0</pose> | ||
<self_collide>0</self_collide> | ||
<inertial auto="true" /> | ||
<visual name="vis_upper_joint"> | ||
<pose>-0.05 0 0 0 1.5708 0</pose> | ||
<geometry> | ||
<cylinder> | ||
<radius>0.1</radius> | ||
<length>0.3</length> | ||
</cylinder> | ||
</geometry> | ||
<material> | ||
<ambient>0.8 0.8 0.8 1</ambient> | ||
<diffuse>0.8 0.8 0.8 1</diffuse> | ||
<specular>0.8 0.8 0.8 1</specular> | ||
</material> | ||
</visual> | ||
<visual name="vis_bob"> | ||
<pose>0 0 1.0 0 1.5708 0</pose> | ||
<geometry> | ||
<cylinder> | ||
<radius>0.1</radius> | ||
<length>0.2</length> | ||
</cylinder> | ||
</geometry> | ||
<material> | ||
<ambient>0.8 0.8 0.8 1</ambient> | ||
<diffuse>0.8 0.8 0.8 1</diffuse> | ||
<specular>0.8 0.8 0.8 1</specular> | ||
</material> | ||
</visual> | ||
<visual name="vis_cylinder"> | ||
<pose>0 0 0.5 0 0 0</pose> | ||
<geometry> | ||
<cylinder> | ||
<radius>0.1</radius> | ||
<length>0.9</length> | ||
</cylinder> | ||
</geometry> | ||
<material> | ||
<ambient>0.8 0.8 0.8 1</ambient> | ||
<diffuse>0.8 0.8 0.8 1</diffuse> | ||
<specular>0.8 0.8 0.8 1</specular> | ||
</material> | ||
</visual> | ||
<collision name="col_upper_joint"> | ||
<density>100</density> | ||
<pose>-0.05 0 0 0 1.5708 0</pose> | ||
<geometry> | ||
<cylinder> | ||
<radius>0.1</radius> | ||
<length>0.3</length> | ||
</cylinder> | ||
</geometry> | ||
</collision> | ||
<collision name="col_bob"> | ||
<density>10000</density> | ||
<pose>0 0 1.0 0 1.5708 0</pose> | ||
<geometry> | ||
<cylinder> | ||
<radius>0.1</radius> | ||
<length>0.3</length> | ||
</cylinder> | ||
</geometry> | ||
</collision> | ||
<collision name="col_cylinder"> | ||
<density>100</density> | ||
<pose>0 0 0.5 0 0 0</pose> | ||
<geometry> | ||
<cylinder> | ||
<radius>0.1</radius> | ||
<length>0.9</length> | ||
</cylinder> | ||
</geometry> | ||
</collision> | ||
</link> | ||
|
||
<!-- pin joint for upper link, at origin of upper link --> | ||
<joint name="upper_joint" type="revolute"> | ||
<parent>base</parent> | ||
<child>upper_link</child> | ||
<axis> | ||
<xyz>1.0 0 0</xyz> | ||
</axis> | ||
</joint> | ||
</model> | ||
|
||
</world> | ||
</sdf> |
Oops, something went wrong.