4 <!-- A global light source -->
8 <!--f550 UAV model connected to default ports -->
10 <uri>model://F550_wireless</uri>
12 <pose>0 0 0 0 0 3.14</pose>
14 <!--Wireless TX point -->
17 <pose>-1 0 0.025 0 0 0</pose>
18 <link name="AP1_link">
25 <size>.05 .05 .05</size>
29 <visual name="antenna">
30 <pose>0 0 .04 0 0 0</pose>
38 <sensor name="wirelessTransmitter" type="wireless_transmitter">
39 <always_on>1</always_on>
40 <update_rate>1</update_rate>
41 <visualize>true</visualize>
44 <frequency>2412.0</frequency>
54 <pose>4 0 0.025 0 0 0</pose>
55 <link name="AP2_link">
62 <size>.05 .05 .05</size>
66 <visual name="antenna">
67 <pose>0 0 .04 0 0 0</pose>
75 <sensor name="wirelessTransmitter" type="wireless_transmitter">
76 <always_on>1</always_on>
77 <update_rate>1</update_rate>
78 <visualize>true</visualize>
81 <frequency>2480.0</frequency>
89 <!-- A ground plane -->
91 <uri>model://ground_plane</uri>
94 <uri>model://asphalt_plane</uri>
96 <physics name='default_physics' default='0' type='ode'>
97 <gravity>0 0 -9.8066</gravity>
103 <use_dynamic_moi_rescaling>0</use_dynamic_moi_rescaling>
108 <contact_max_correcting_vel>100</contact_max_correcting_vel>
109 <contact_surface_layer>0.001</contact_surface_layer>
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>