iris_simple.urdf 4.94 KB
Newer Older
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
<?xml version="1.0" ?>
<robot name="iris">
  <joint name="iris__/imu_joint" type="fixed">
    <parent link="iris__base_link"/>
    <child link="iris__/imu_link"/>
    <origin rpy="0  0  0" xyz="0  0  0"/>
    <axis xyz="1  0  0"/>
    <limit effort="0.0" lower="0.0" upper="0.0" velocity="0.0"/>
  </joint>
  <joint name="iris__rotor_0_joint" type="fixed">
    <parent link="iris__base_link"/>
    <child link="iris__rotor_0"/>
    <origin rpy="0  0  0" xyz="0.13  -0.22   0.023"/>
    <axis xyz="0  0  1"/>
    <limit effort="0.0" lower="-1e+16" upper="1e+16" velocity="0.0"/>
  </joint>
  <joint name="iris__rotor_1_joint" type="fixed">
    <parent link="iris__base_link"/>
    <child link="iris__rotor_1"/>
    <origin rpy="0  0  0" xyz="-0.13   0.2    0.023"/>
    <axis xyz="0  0  1"/>
    <limit effort="0.0" lower="-1e+16" upper="1e+16" velocity="0.0"/>
  </joint>
  <joint name="iris__rotor_2_joint" type="fixed">
    <parent link="iris__base_link"/>
    <child link="iris__rotor_2"/>
    <origin rpy="0  0  0" xyz="0.13   0.22   0.023"/>
    <axis xyz="0  0  1"/>
    <limit effort="0.0" lower="-1e+16" upper="1e+16" velocity="0.0"/>
  </joint>
  <joint name="iris__rotor_3_joint" type="fixed">
    <parent link="iris__base_link"/>
    <child link="iris__rotor_3"/>
    <origin rpy="0  0  0" xyz="-0.13  -0.2    0.023"/>
    <axis xyz="0  0  1"/>
    <limit effort="0.0" lower="-1e+16" upper="1e+16" velocity="0.0"/>
  </joint>
  <link name="iris__base_link">
    <inertial>
      <mass value="1.5"/>
      <origin rpy="0  0  0" xyz="0  0  0"/>
      <inertia ixx="0.029125" ixy="0" ixz="0" iyy="0.029125" iyz="0" izz="0.055225"/>
    </inertial>
    <collision name="iris__base_link_inertia_collision">
      <origin rpy="0  0  0" xyz="0  0  0"/>
      <geometry>
        <box size="0.47 0.47 0.11"/>
      </geometry>
    </collision>
    <visual name="iris__base_link_inertia_visual">
      <origin rpy="0  0  0" xyz="0  0  0"/>
      <geometry>
53
        <mesh filename="package://example-robot-data/robots/iris_description/meshes/iris.stl" scale="1 1 1"/>
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
      </geometry>
    </visual>
  </link>
  <link name="iris__/imu_link">
    <inertial>
      <mass value="0.015"/>
      <origin rpy="0  0  0" xyz="0  0  0"/>
      <inertia ixx="1e-05" ixy="0" ixz="0" iyy="1e-05" iyz="0" izz="1e-05"/>
    </inertial>
  </link>
  <link name="iris__rotor_0">
    <inertial>
      <mass value="0.005"/>
      <origin rpy="0  0  0" xyz="0  0  0"/>
      <inertia ixx="9.75e-07" ixy="0" ixz="0" iyy="0.000273104" iyz="0" izz="0.000274004"/>
    </inertial>
    <collision name="iris__rotor_0_collision">
      <origin rpy="0  0  0" xyz="0  0  0"/>
      <geometry>
        <cylinder length="0.005" radius="0.128"/>
      </geometry>
    </collision>
    <visual name="iris__rotor_0_visual">
      <origin rpy="0  0  0" xyz="0  0  0"/>
      <geometry>
79
        <mesh filename="package://example-robot-data/robots/iris_description/meshes/iris_prop_ccw.dae" scale="1 1 1"/>
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
      </geometry>
    </visual>
  </link>
  <link name="iris__rotor_1">
    <inertial>
      <mass value="0.005"/>
      <origin rpy="0  0  0" xyz="0 0 0"/>
      <inertia ixx="9.75e-07" ixy="0" ixz="0" iyy="0.000273104" iyz="0" izz="0.000274004"/>
    </inertial>
    <collision name="iris__rotor_1_collision">
      <origin rpy="0  0  0" xyz="0  0  0"/>
      <geometry>
        <cylinder length="0.005" radius="0.128"/>
      </geometry>
    </collision>
    <visual name="iris__rotor_1_visual">
      <origin rpy="0  0  0" xyz="0  0  0"/>
      <geometry>
98
        <mesh filename="package://example-robot-data/robots/iris_description/meshes/iris_prop_ccw.dae" scale="1 1 1"/>
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
      </geometry>
    </visual>
  </link>
  <link name="iris__rotor_2">
    <inertial>
      <mass value="0.005"/>
      <origin rpy="0  0  0" xyz="0  0  0"/>
      <inertia ixx="9.75e-07" ixy="0" ixz="0" iyy="0.000273104" iyz="0" izz="0.000274004"/>
    </inertial>
    <collision name="iris__rotor_2_collision">
      <origin rpy="0  0  0" xyz="0  0  0"/>
      <geometry>
        <cylinder length="0.005" radius="0.128"/>
      </geometry>
    </collision>
    <visual name="iris__rotor_2_visual">
      <origin rpy="0  0  0" xyz="0  0  0"/>
      <geometry>
117
        <mesh filename="package://example-robot-data/robots/iris_description/meshes/iris_prop_cw.dae" scale="1 1 1"/>
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
      </geometry>
    </visual>
  </link>
  <link name="iris__rotor_3">
    <inertial>
      <mass value="0.005"/>
      <origin rpy="0  0  0" xyz="0  0  0"/>
      <inertia ixx="9.75e-07" ixy="0" ixz="0" iyy="0.000273104" iyz="0" izz="0.000274004"/>
    </inertial>
    <collision name="iris__rotor_3_collision">
      <origin rpy="0  0  0" xyz="0  0  0"/>
      <geometry>
        <cylinder length="0.005" radius="0.128"/>
      </geometry>
    </collision>
    <visual name="iris__rotor_3_visual">
      <origin rpy="0  0  0" xyz="0  0  0"/>
      <geometry>
136
        <mesh filename="package://example-robot-data/robots/iris_description/meshes/iris_prop_cw.dae" scale="1 1 1"/>
137
138
139
140
      </geometry>
    </visual>
  </link>
</robot>