-
Notifications
You must be signed in to change notification settings - Fork 28
/
Copy pathcrazyflie.xacro
158 lines (146 loc) · 6.61 KB
/
crazyflie.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
158
<?xml version="1.0"?>
<!--
Copyright 2018 Eric Goubault, Cosynus, LIX, France
Copyright 2018 Sylve Putot, Cosynus, LIX, France
Copyright 2018 Franck Djeumou, Cosynus, LIX, France
-->
<robot name="crazyflie" xmlns:xacro="http://ros.org/wiki/xacro">
<!-- Properties -->
<xacro:property name="namespace" value="$(arg namespace)" />
<xacro:property name="rotor_velocity_slowdown_sim" value="70" />
<xacro:property name="mesh_file" value="crazyflie.dae" />
<xacro:property name="mesh_scale" value="1 1 1"/>
<xacro:property name="mesh_prop_file" value="crazyflie_prop.dae" />
<xacro:property name="mesh_scale_prop" value="1 1 1"/>
<xacro:property name="color_prop_front" value="$(arg color_prop_front)"/>
<xacro:property name="color_prop_back" value="$(arg color_prop_back)"/>
<xacro:property name="mass" value="0.025" /> <!-- [kg] -->
<xacro:property name="body_width" value="0.07" /> <!-- [m] -->
<xacro:property name="body_height" value="0.025" /> <!-- [m] -->
<xacro:property name="mass_rotor" value="0.00075" /> <!-- [kg] -->
<xacro:property name="arm_length_front_x" value="0.03252691193" /> <!-- [m] -->
<xacro:property name="arm_length_back_x" value="0.03252691193" /> <!-- [m] -->
<xacro:property name="arm_length_front_y" value="0.03252691193" /> <!-- [m] -->
<xacro:property name="arm_length_back_y" value="0.03252691193" /> <!-- [m] -->
<xacro:property name="rotor_offset_top" value="0.0125" /> <!-- [m] -->
<xacro:property name="radius_rotor" value="0.0225" /> <!-- [m] -->
<xacro:property name="motor_constant" value="1.2819184e-8" /> <!-- [kg.m/s^2] -->
<xacro:property name="moment_constant" value="0.005964552" /> <!-- [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="3052" /> <!-- [rad/s] -->
<xacro:property name="rotor_drag_coefficient" value="9.1785e-7" />
<xacro:property name="rolling_moment_coefficient" value="0.0000001" />
<!-- Property Blocks -->
<xacro:property name="body_inertia">
<inertia ixx="1.657171e-5" ixy="0.830806e-6" ixz="0.718277e-6" iyy="1.6655602e-5" iyz="1.800197e-6" izz="2.9261652e-5" /> <!-- [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=0.3mm, width=0.9mm -->
<xacro:property name="rotor_inertia">
<inertia
ixx="${1/12 * mass_rotor * (0.006 * 0.006 + 0.001 * 0.001) * rotor_velocity_slowdown_sim}"
iyy="${1/12 * mass_rotor * (4 * radius_rotor * radius_rotor + 0.001 * 0.001) * rotor_velocity_slowdown_sim}"
izz="${1/12 * mass_rotor * (4 * radius_rotor * radius_rotor + 0.006 * 0.006) * rotor_velocity_slowdown_sim}"
ixy="0.0" ixz="0.0" iyz="0.0" /> <!-- [kg.m^2] [kg.m^2] [kg.m^2] [kg.m^2] [kg.m^2] [kg.m^2] -->
</xacro:property>
<!-- Included URDF Files -->
<xacro:include filename="$(arg rotors_description_dir)/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}"
mesh_file="${mesh_file}"
mesh_scale="${mesh_scale}"
>
<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="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="${color_prop_front}"
use_own_mesh="true"
mesh_scale="${mesh_scale_prop}"
mesh="${mesh_prop_file}">
<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="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="${color_prop_back}"
use_own_mesh="true"
mesh_scale="${mesh_scale_prop}"
mesh="${mesh_prop_file}">
<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="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="${color_prop_front}"
use_own_mesh="true"
mesh_scale="${mesh_scale_prop}"
mesh="${mesh_prop_file}">
<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="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="${color_prop_back}"
use_own_mesh="true"
mesh_scale="${mesh_scale_prop}"
mesh="${mesh_prop_file}">
<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>