-
Notifications
You must be signed in to change notification settings - Fork 84
/
iris.xacro
142 lines (132 loc) · 5.75 KB
/
iris.xacro
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
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
<?xml version="1.0"?>
<robot name="iris" xmlns:xacro="http://ros.org/wiki/xacro">
<!-- Properties -->
<xacro:property name="namespace" value="$(arg namespace)" />
<xacro:property name="rotor_velocity_slowdown_sim" value="10" />
<xacro:property name="use_mesh_file" value="true" />
<xacro:property name="mesh_file" value="package://rotors_description/meshes/iris.dae" />
<xacro:property name="mass" value="1.5" /> <!-- [kg] -->
<xacro:property name="body_width" value="0.47" /> <!-- [m] -->
<xacro:property name="body_height" value="0.11" /> <!-- [m] -->
<xacro:property name="mass_rotor" value="0.005" /> <!-- [kg] -->
<xacro:property name="arm_length_front_x" value="0.13" /> <!-- [m] -->
<xacro:property name="arm_length_back_x" value="0.13" /> <!-- [m] -->
<xacro:property name="arm_length_front_y" value="0.22" /> <!-- [m] -->
<xacro:property name="arm_length_back_y" value="0.2" /> <!-- [m] -->
<xacro:property name="rotor_offset_top" value="0.023" /> <!-- [m] -->
<xacro:property name="radius_rotor" value="0.1" /> <!-- [m] -->
<xacro:property name="motor_constant" value="8.54858e-06" /> <!-- [kg.m/s^2] -->
<xacro:property name="moment_constant" value="0.016" /> <!-- [m] -->
<xacro:property name="time_constant_up" value="0.0125" /> <!-- [s] -->
<xacro:property name="time_constant_down" value="0.025" /> <!-- [s] -->
<xacro:property name="max_rot_velocity" value="838" /> <!-- [rad/s] -->
<xacro:property name="sin30" value="0.5" />
<xacro:property name="cos30" value="0.866025403784" />
<xacro:property name="sqrt2" value="1.4142135623730951" />
<xacro:property name="rotor_drag_coefficient" value="8.06428e-05" />
<xacro:property name="rolling_moment_coefficient" value="0.000001" />
<!-- Property Blocks -->
<xacro:property name="body_inertia">
<inertia ixx="0.0347563" ixy="0.0" ixz="0.0" iyy="0.0458929" iyz="0.0" izz="0.0977" /> <!-- [kg.m^2] [kg.m^2] [kg.m^2] [kg.m^2] [kg.m^2] [kg.m^2] -->
</xacro:property>
<!-- inertia of a single rotor, assuming it is a cuboid. Height=3mm, width=15mm -->
<xacro:property name="rotor_inertia">
<xacro:box_inertia x="${radius_rotor}" y="0.015" z="0.003" mass="${mass_rotor*rotor_velocity_slowdown_sim}" />
</xacro:property>
<!-- Included URDF Files -->
<xacro:include filename="$(find rotors_description)/urdf/multirotor_base.xacro" />
<!-- Instantiate multirotor_base_macro once -->
<xacro:multirotor_base_macro
robot_namespace="${namespace}"
mass="${mass}"
body_width="${body_width}"
body_height="${body_height}"
use_mesh_file="${use_mesh_file}"
mesh_file="${mesh_file}"
>
<xacro:insert_block name="body_inertia" />
</xacro:multirotor_base_macro>
<!-- Instantiate rotors -->
<xacro:vertical_rotor
robot_namespace="${namespace}"
suffix="front_right"
direction="ccw"
motor_constant="${motor_constant}"
moment_constant="${moment_constant}"
parent="${namespace}/base_link"
mass_rotor="${mass_rotor}"
radius_rotor="${radius_rotor}"
time_constant_up="${time_constant_up}"
time_constant_down="${time_constant_down}"
max_rot_velocity="${max_rot_velocity}"
motor_number="0"
rotor_drag_coefficient="${rotor_drag_coefficient}"
rolling_moment_coefficient="${rolling_moment_coefficient}"
color="Blue"
use_own_mesh="false"
mesh="">
<origin xyz="${arm_length_front_x} -${arm_length_front_y} ${rotor_offset_top}" rpy="0 0 0" />
<xacro:insert_block name="rotor_inertia" />
</xacro:vertical_rotor>
<xacro:vertical_rotor
robot_namespace="${namespace}"
suffix="back_left"
direction="ccw"
motor_constant="${motor_constant}"
moment_constant="${moment_constant}"
parent="${namespace}/base_link"
mass_rotor="${mass_rotor}"
radius_rotor="${radius_rotor}"
time_constant_up="${time_constant_up}"
time_constant_down="${time_constant_down}"
max_rot_velocity="${max_rot_velocity}"
motor_number="1"
rotor_drag_coefficient="${rotor_drag_coefficient}"
rolling_moment_coefficient="${rolling_moment_coefficient}"
color="Red"
use_own_mesh="false"
mesh="">
<origin xyz="-${arm_length_back_x} ${arm_length_back_y} ${rotor_offset_top}" rpy="0 0 0" />
<xacro:insert_block name="rotor_inertia" />
</xacro:vertical_rotor>
<xacro:vertical_rotor robot_namespace="${namespace}"
suffix="front_left"
direction="cw"
motor_constant="${motor_constant}"
moment_constant="${moment_constant}"
parent="${namespace}/base_link"
mass_rotor="${mass_rotor}"
radius_rotor="${radius_rotor}"
time_constant_up="${time_constant_up}"
time_constant_down="${time_constant_down}"
max_rot_velocity="${max_rot_velocity}"
motor_number="2"
rotor_drag_coefficient="${rotor_drag_coefficient}"
rolling_moment_coefficient="${rolling_moment_coefficient}"
color="Blue"
use_own_mesh="false"
mesh="">
<origin xyz="${arm_length_front_x} ${arm_length_front_y} ${rotor_offset_top}" rpy="0 0 0" />
<xacro:insert_block name="rotor_inertia" />
</xacro:vertical_rotor>
<xacro:vertical_rotor robot_namespace="${namespace}"
suffix="back_right"
direction="cw"
motor_constant="${motor_constant}"
moment_constant="${moment_constant}"
parent="${namespace}/base_link"
mass_rotor="${mass_rotor}"
radius_rotor="${radius_rotor}"
time_constant_up="${time_constant_up}"
time_constant_down="${time_constant_down}"
max_rot_velocity="${max_rot_velocity}"
motor_number="3"
rotor_drag_coefficient="${rotor_drag_coefficient}"
rolling_moment_coefficient="${rolling_moment_coefficient}"
color="Red"
use_own_mesh="false"
mesh="">
<origin xyz="-${arm_length_back_x} -${arm_length_back_y} ${rotor_offset_top}" rpy="0 0 0" />
<xacro:insert_block name="rotor_inertia" />
</xacro:vertical_rotor>
</robot>