yosemite.world
1.43 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
<?xml version="1.0" ?>
<sdf version="1.5">
<world name="default">
<scene>
<sky>
<clouds>
<speed>12</speed>
</clouds>
</sky>
<ambient>0.95 0.95 0.95 1</ambient>
<background>0.3 0.3 0.3 1</background>
<shadows>true</shadows>
</scene>
<!-- A global light source -->
<include>
<uri>model://sun</uri>
</include>
<include>
<uri>model://yosemite</uri>
</include>
<spherical_coordinates>
<surface_model>EARTH_WGS84</surface_model>
<latitude_deg>37.7332531</latitude_deg>
<longitude_deg>-119.5616378</longitude_deg>
<elevation>2800.4</elevation>
</spherical_coordinates>
<physics name='default_physics' default='0' type='ode'>
<gravity>0 0 -9.8066</gravity>
<ode>
<solver>
<type>quick</type>
<iters>10</iters>
<sor>1.3</sor>
<use_dynamic_moi_rescaling>0</use_dynamic_moi_rescaling>
</solver>
<constraints>
<cfm>0</cfm>
<erp>0.2</erp>
<contact_max_correcting_vel>100</contact_max_correcting_vel>
<contact_surface_layer>0.001</contact_surface_layer>
</constraints>
</ode>
<max_step_size>0.004</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>250</real_time_update_rate>
<magnetic_field>6.0e-6 2.3e-5 -4.2e-5</magnetic_field>
</physics>
</world>
</sdf>