-
Notifications
You must be signed in to change notification settings - Fork 765
/
hummingbird.xacro
157 lines (144 loc) · 6.18 KB
/
hummingbird.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
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
<?xml version="1.0"?>
<!--
Copyright 2015 Fadri Furrer, ASL, ETH Zurich, Switzerland
Copyright 2015 Michael Burri, ASL, ETH Zurich, Switzerland
Copyright 2015 Mina Kamel, ASL, ETH Zurich, Switzerland
Copyright 2015 Janosch Nikolic, ASL, ETH Zurich, Switzerland
Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
-->
<robot name="hummingbird" xmlns:xacro="http://ros.org/wiki/xacro">
<!-- Properties (Taken from Novel Dynamic Inversion Architecture Design
for Quadrocopter Control by Jian Wang et al.) -->
<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/hummingbird.dae" />
<xacro:property name="mass" value="0.68" /> <!-- [kg] -->
<xacro:property name="body_width" value="0.1" /> <!-- [m] -->
<xacro:property name="body_height" value="0.12" /> <!-- [m] -->
<xacro:property name="mass_rotor" value="0.009" /> <!-- [kg] -->
<xacro:property name="arm_length" value="0.17" /> <!-- [m] -->
<xacro:property name="rotor_offset_top" value="0.01" /> <!-- [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="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.007" ixy="0.0" ixz="0.0" iyy="0.007" iyz="0.0" izz="0.012" /> <!-- [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"
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="0"
rotor_drag_coefficient="${rotor_drag_coefficient}"
rolling_moment_coefficient="${rolling_moment_coefficient}"
color="Red"
use_own_mesh="false"
mesh="">
<origin xyz="${arm_length} 0 ${rotor_offset_top}" rpy="0 0 0" />
<xacro:insert_block name="rotor_inertia" />
</xacro:vertical_rotor>
<xacro:vertical_rotor
robot_namespace="${namespace}"
suffix="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="Blue"
use_own_mesh="false"
mesh="">
<origin xyz="0 ${arm_length} ${rotor_offset_top}" rpy="0 0 0" />
<xacro:insert_block name="rotor_inertia" />
</xacro:vertical_rotor>
<xacro:vertical_rotor
robot_namespace="${namespace}"
suffix="back"
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} 0 ${rotor_offset_top}" rpy="0 0 0" />
<xacro:insert_block name="rotor_inertia" />
</xacro:vertical_rotor>
<xacro:vertical_rotor
robot_namespace="${namespace}"
suffix="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="3"
rotor_drag_coefficient="${rotor_drag_coefficient}"
rolling_moment_coefficient="${rolling_moment_coefficient}"
color="Blue"
use_own_mesh="false"
mesh="">
<origin xyz="0 -${arm_length} ${rotor_offset_top}" rpy="0 0 0" />
<xacro:insert_block name="rotor_inertia" />
</xacro:vertical_rotor>
</robot>