forked from jackfetkovich/ECE592-Final-Project
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathproject.xml
More file actions
95 lines (76 loc) · 4.01 KB
/
project.xml
File metadata and controls
95 lines (76 loc) · 4.01 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
<mujoco model="auv">
<!-- Density and Viscosity tuned to represent fluid environment -->
<option timestep="0.0001" density="1000" viscosity="1e-6" cone="elliptic" noslip_iterations="3"/>
<asset>
<!-- Floor Asset Definition -->
<texture name="grid" type="2d" builtin="checker" rgb1=".1 .2 .3"
rgb2=".2 .3 .4" width="300" height="300" mark="edge" markrgb=".2 .3 .4"/>
<material name="grid" texture="grid" texrepeat="2 2" texuniform="true"
reflectance=".2"/>
</asset>
<worldbody>
<light name="top" pos="0 0 10"/>
<geom size="10 10 .01" type="plane" material="grid"/>
<!-- SeaWolf IX AUV model -->
<body name="SWIX" pos="0 0 5">
<site name="imu" pos="0 0 0"/>
<freejoint name="SWIX_freejoint"/>
<!-- AUV Frame -->
<geom name="red_box" type="box" size=".4 .2 .2" rgba="1 0 0 0.3" pos="0 0 0" mass="100"/>
<!-- Vertical Thrusters -->
<body name="thruster_2" pos=".2 -.3 0">
<geom type="cylinder" size=".1 .1" rgba="0 0 0 1" mass=".1"/>
</body>
<site name="thrust2_site" pos=".2 -.2 0"/>
<body name="thruster_3" pos="-.2 -.3 0">
<geom type="cylinder" size=".1 .1" rgba="0 0 0 1" mass=".1"/>
</body>
<site name="thrust3_site" pos="-.2 -.2 0"/>
<body name="thruster6" pos="-.2 .3 0">
<geom type="cylinder" size=".1 .1" rgba="0 0 0 1" mass=".1"/>
</body>
<site name="thrust6_site" pos="-.2 .2 0"/>
<body name="thruster_7" pos=".2 .3 0">
<geom type="cylinder" size=".1 .1" rgba="0 0 0 1" mass=".1"/>
</body>
<site name="thrust7_site" pos=".2 .2 0"/>
<!-- Diagonal Thrusters -->
<body name="thruster_0" pos=".45 .25 0" euler="90 45 0">
<geom type="cylinder" size=".1 .1" rgba="0 0 0 1" mass=".1"/>
</body>
<site name="thrust0_site" pos=".4 .2 0"/>
<body name="thruster_1" pos=".45 -.25 0" euler="90 135 0">
<geom type="cylinder" size=".1 .1" rgba="0 0 0 1" mass=".1"/>
</body>
<site name="thrust1_site" pos=".4 -.2 0"/>
<body name="thruster_4" pos="-.45 -.25 0" euler="90 45 0">
<geom type="cylinder" size=".1 .1" rgba="0 0 0 1" mass=".1"/>
</body>
<site name="thrust4_site" pos="-.4 -.2 0"/>
<body name="thruster_5" pos="-.45 .25 0" euler="90 135 0">
<geom type="cylinder" size=".1 .1" rgba="0 0 0 1" mass=".1"/>
</body>
<site name="thrust5_site" pos="-.4 .2 0"/>
</body>
</worldbody>
<actuator>
<!-- Front Diagonal Thrusters -->
<motor name="thrust0" site="thrust0_site" gear=".4472 -.8944 0 0 0 0" ctrlrange="-500 500"/>
<motor name="thrust1" site="thrust1_site" gear=".4473 .8944 0 0 0 0" ctrlrange="-500 500"/>
<!-- Right Vertical Thrusters -->
<motor name="thrust2" site="thrust2_site" gear="0 0 -1 0 0 0" ctrlrange="-500 500"/>
<motor name="thrust3" site="thrust3_site" gear="0 0 -1 0 0 0" ctrlrange="-500 500"/>
<!-- Back Diagonal Thrusters -->
<motor name="thrust4" site="thrust4_site" gear=".4473 -.8944 0 0 0 0" ctrlrange="-500 500"/>
<motor name="thrust5" site="thrust5_site" gear=".4473 .8944 0 0 0 0" ctrlrange="-500 500"/>
<!-- Left Vertical Thrusters -->
<motor name="thrust6" site="thrust6_site" gear="0 0 -1 0 0 0" ctrlrange="-500 500"/>
<motor name="thrust7" site="thrust7_site" gear="0 0 -1 0 0 0" ctrlrange="-500 500"/>
</actuator>
<sensor>
<framepos name="body_pos" objtype="site" objname="imu"/>
<framequat name="body_orientation" objtype="site" objname="imu"/>
<framelinvel name="body_linvel" objtype="site" objname="imu"/>
<frameangvel name="body_angvel" objtype="site" objname="imu"/>
</sensor>
</mujoco>