forked from ctu-mrs/mrs_gazebo_common_resources
-
Notifications
You must be signed in to change notification settings - Fork 0
/
uneven_plane.world
94 lines (83 loc) · 2.72 KB
/
uneven_plane.world
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
<?xml version="1.0" ?>
<?xml-model href="http://sdformat.org/schemas/root.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<sdf version="1.5">
<world name="default">
<!-- <plugin name="mrs_gazebo_link_attacher_plugin" filename="libMRSGazeboLinkAttacherPlugin.so"/> -->
<plugin name="mrs_gazebo_static_transform_republisher_plugin" filename="libMRSGazeboStaticTransformRepublisher.so"/>
<!-- coordinate system {-->
<spherical_coordinates>
<surface_model>EARTH_WGS84</surface_model>
<latitude_deg>47.397743</latitude_deg>
<longitude_deg>8.545594</longitude_deg>
<elevation>0.0</elevation>
<heading_deg>0</heading_deg>
</spherical_coordinates>
<!--}-->
<!-- physics engine {-->
<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>1000</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-06 2.3e-05 -4.2e-05</magnetic_field>
</physics>
<!--}-->
<!-- turn off shadows {-->
<scene>
<shadows>false</shadows>
<sky>
<clouds/>
</sky>
</scene>
<!--}-->
<!-- sun {-->
<light name='sun' type='directional'>
<pose frame=''>0 0 1000 0 -0 0</pose>
<diffuse>0.5 0.5 0.5 1</diffuse>
<specular>0.1 0.1 0.1 1</specular>
<direction>0.1 0.1 -0.9</direction>
<attenuation>
<range>20</range>
<constant>0.5</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<cast_shadows>1</cast_shadows>
</light>
<!--}-->
<!-- world {-->
<include>
<uri>model://uneven_plane</uri>
<pose>0 0 0 0 0 0</pose>
</include>
<!--}-->
<!-- user camera {-->
<gui>
<camera name="camera">
<pose>-60 -100 30 0 0.4 0.89</pose>
</camera>
</gui>
<!--}-->
<!-- GUI frame synchronization {-->
<plugin name="mrs_gazebo_rviz_cam_synchronizer" filename="libMRSGazeboRvizCameraSynchronizer.so" >
<target_frame_id>gazebo_user_camera</target_frame_id>
<world_origin_frame_id>uav1/gps_origin</world_origin_frame_id>
<frame_to_follow>uav1::base_link</frame_to_follow>
</plugin>
<!--}-->
</world>
</sdf>