PX4 simulation stack
wireless_test.world
Go to the documentation of this file.
1 <?xml version="1.0" ?>
2 <sdf version="1.5">
3  <world name="default">
4  <!-- A global light source -->
5  <include>
6  <uri>model://sun</uri>
7  </include>
8  <!--f550 UAV model connected to default ports -->
9  <include>
10  <uri>model://F550_wireless</uri>
11  <name>f550_wl</name>
12  <pose>0 0 0 0 0 3.14</pose>
13  </include>
14 <!--Wireless TX point -->
15 <model name="AP1">
16  <static>true</static>
17  <pose>-1 0 0.025 0 0 0</pose>
18  <link name="AP1_link">
19  <inertial>
20  <mass>0.1</mass>
21  </inertial>
22  <visual name="base">
23  <geometry>
24  <box>
25  <size>.05 .05 .05</size>
26  </box>
27  </geometry>
28  </visual>
29  <visual name="antenna">
30  <pose>0 0 .04 0 0 0</pose>
31  <geometry>
32  <cylinder>
33  <radius>.005</radius>
34  <length>.07</length>
35  </cylinder>
36  </geometry>
37  </visual>
38  <sensor name="wirelessTransmitter" type="wireless_transmitter">
39  <always_on>1</always_on>
40  <update_rate>1</update_rate>
41  <visualize>true</visualize>
42  <transceiver>
43  <essid>AP1</essid>
44  <frequency>2412.0</frequency>
45  <power>14.5</power>
46  <gain>2.6</gain>
47  </transceiver>
48  </sensor>
49  </link>
50 </model>
51 
52 <model name="AP2">
53  <static>true</static>
54  <pose>4 0 0.025 0 0 0</pose>
55  <link name="AP2_link">
56  <inertial>
57  <mass>0.1</mass>
58  </inertial>
59  <visual name="base">
60  <geometry>
61  <box>
62  <size>.05 .05 .05</size>
63  </box>
64  </geometry>
65  </visual>
66  <visual name="antenna">
67  <pose>0 0 .04 0 0 0</pose>
68  <geometry>
69  <cylinder>
70  <radius>.005</radius>
71  <length>.07</length>
72  </cylinder>
73  </geometry>
74  </visual>
75  <sensor name="wirelessTransmitter" type="wireless_transmitter">
76  <always_on>1</always_on>
77  <update_rate>1</update_rate>
78  <visualize>true</visualize>
79  <transceiver>
80  <essid>AP2</essid>
81  <frequency>2480.0</frequency>
82  <power>15</power>
83  <gain>5</gain>
84  </transceiver>
85  </sensor>
86  </link>
87 </model>
88 
89  <!-- A ground plane -->
90  <include>
91  <uri>model://ground_plane</uri>
92  </include>
93  <include>
94  <uri>model://asphalt_plane</uri>
95  </include>
96  <physics name='default_physics' default='0' type='ode'>
97  <gravity>0 0 -9.8066</gravity>
98  <ode>
99  <solver>
100  <type>quick</type>
101  <iters>10</iters>
102  <sor>1.3</sor>
103  <use_dynamic_moi_rescaling>0</use_dynamic_moi_rescaling>
104  </solver>
105  <constraints>
106  <cfm>0</cfm>
107  <erp>0.2</erp>
108  <contact_max_correcting_vel>100</contact_max_correcting_vel>
109  <contact_surface_layer>0.001</contact_surface_layer>
110  </constraints>
111  </ode>
112  <max_step_size>0.002</max_step_size>
113  <real_time_factor>1</real_time_factor>
114  <real_time_update_rate>500</real_time_update_rate>
115  <magnetic_field>6.0e-6 2.3e-5 -4.2e-5</magnetic_field>
116  </physics>
117  </world>
118 </sdf>