File: wireless_sensors.world

package info (click to toggle)
gazebo 9.6.0-1
  • links: PTS, VCS
  • area: main
  • in suites: buster
  • size: 115,400 kB
  • sloc: cpp: 356,787; xml: 20,974; ansic: 9,594; python: 2,417; sh: 395; ruby: 375; makefile: 62
file content (88 lines) | stat: -rw-r--r-- 2,460 bytes parent folder | download | duplicates (4)
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
<?xml version="1.0" ?>
<sdf version="1.5">
  <world name="default">
    <!-- Ground -->
    <include>
      <uri>model://ground_plane</uri>
    </include>
    <!-- Wireless transmitter sensor model -->
    <model name="wirelessTransmitter">
      <static>true</static>
      <pose>0 0 0.025 0 0 0</pose>
      <link name="link">
        <inertial>
          <mass>0.1</mass>
        </inertial>
        <visual name="base">
          <geometry>
            <box>
              <size>.05 .05 .05</size>
            </box>
          </geometry>
        </visual>
        <visual name="antenna">
          <pose>0 0 .04 0 0 0</pose>
          <geometry>
            <cylinder>
              <radius>.005</radius>
              <length>.07</length>
            </cylinder>
          </geometry>
        </visual>
        <sensor name="wirelessTransmitter" type="wireless_transmitter">
          <always_on>1</always_on>
          <update_rate>1</update_rate>
          <visualize>true</visualize>
          <transceiver>
            <essid>osrf</essid>
            <frequency>2442.0</frequency>
            <power>14.5</power>
            <gain>2.6</gain>
          </transceiver>
        </sensor>
      </link>
    </model>
    <!-- Wireless receiver sensor model -->
    <model name="wirelessReceiver">
      <static>true</static>
      <pose>0 -3 0.025 0 0 0</pose>
      <link name="link">
        <inertial>
          <mass>0.1</mass>
        </inertial>
        <visual name="base">
          <geometry>
            <box>
              <size>.05 .05 .05</size>
            </box>
          </geometry>
        </visual>
        <visual name="antenna">
          <pose>0 0 .04 0 0 0</pose>
          <geometry>
            <cylinder>
              <radius>.005</radius>
              <length>.07</length>
            </cylinder>
          </geometry>
        </visual>
        <sensor name="wirelessReceiver" type="wireless_receiver">
          <always_on>1</always_on>
          <update_rate>1</update_rate>
          <visualize>true</visualize>
          <transceiver>
            <min_frequency>2412.0</min_frequency>
            <max_frequency>2484.0</max_frequency>
            <power>14.5</power>
            <gain>2.5</gain>
            <sensitivity>-90.0</sensitivity>
          </transceiver>
        </sensor>
      </link>
    </model>
    <!-- A global light source -->
    <include>
      <uri>model://sun</uri>
    </include>
  </world>
</sdf>