/
quadrotor_px4fmu.xml
209 lines (174 loc) · 7.87 KB
/
quadrotor_px4fmu.xml
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
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
<!DOCTYPE airframe SYSTEM "../airframe.dtd">
<!-- this is a quadrotor frame equiped with
* Autopilot: PX4FMU 1.7 https://pixhawk.ethz.ch/px4/modules/px4fmu
* IMU: MPU6000 + HMC5883 http://wiki.paparazziuav.org/wiki/AspirinIMU
* Actuators: PWM motor controllers http://wiki.paparazziuav.org/wiki/Subsystem/actuators#PWM_Supervision
* GPS: Ublox http://wiki.paparazziuav.org/wiki/Subsystem/gps
* RC: PPM http://wiki.paparazziuav.org/wiki/Subsystem/radio_control#PPM
-->
<airframe name="Quadrotor PX4FMU 1.7">
<firmware name="rotorcraft">
<target name="ap" board="px4fmu_1.7"/>
<target name="nps" board="pc">
<subsystem name="fdm" type="jsbsim"/>
</target>
<subsystem name="motor_mixing"/>
<subsystem name="actuators" type="pwm">
<define name="SERVO_HZ" value="400"/>
</subsystem>
<subsystem name="radio_control" type="ppm"/>
<subsystem name="telemetry" type="transparent"/>
<subsystem name="imu" type="px4fmu_v1.7"/>
<subsystem name="gps" type="ublox"/>
<subsystem name="stabilization" type="int_quat"/>
<subsystem name="ahrs" type="int_cmpl_quat">
<define name="AHRS_GRAVITY_UPDATE_NORM_HEURISTIC" value="TRUE"/>
</subsystem>
<subsystem name="ins"/>
</firmware>
<modules main_freq="512">
<load name="sys_mon.xml"/>
<load name="gps_ubx_ucenter.xml"/>
</modules>
<servos driver="Pwm">
<servo name="FRONT" no="0" min="1000" neutral="1100" max="1900"/>
<servo name="BACK" no="1" min="1000" neutral="1100" max="1900"/>
<servo name="RIGHT" no="2" min="1000" neutral="1100" max="1900"/>
<servo name="LEFT" no="3" min="1000" neutral="1100" max="1900"/>
</servos>
<commands>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="THRUST" failsafe_value="0"/>
</commands>
<section name="MIXING" prefix="MOTOR_MIXING_">
<define name="TRIM_ROLL" value="0"/>
<define name="TRIM_PITCH" value="0"/>
<define name="TRIM_YAW" value="0"/>
<define name="NB_MOTOR" value="4"/>
<define name="SCALE" value="256"/>
<!-- front/back turning CW, right/left CCW -->
<define name="ROLL_COEF" value="{ 0, 0, -256, 256 }"/>
<define name="PITCH_COEF" value="{ 256, -256, 0, 0 }"/>
<define name="YAW_COEF" value="{ -256, -256, 256, 256 }"/>
<define name="THRUST_COEF" value="{ 256, 256, 256, 256 }"/>
</section>
<command_laws>
<call fun="motor_mixing_run(autopilot_motors_on,FALSE,values)"/>
<set servo="FRONT" value="motor_mixing.commands[0]"/>
<set servo="BACK" value="motor_mixing.commands[1]"/>
<set servo="RIGHT" value="motor_mixing.commands[2]"/>
<set servo="LEFT" value="motor_mixing.commands[3]"/>
</command_laws>
<section name="IMU" prefix="IMU_">
<define name="ACCEL_X_NEUTRAL" value="11"/>
<define name="ACCEL_Y_NEUTRAL" value="11"/>
<define name="ACCEL_Z_NEUTRAL" value="-25"/>
<!-- replace this with your own calibration -->
<define name="MAG_X_NEUTRAL" value="-179"/>
<define name="MAG_Y_NEUTRAL" value="-21"/>
<define name="MAG_Z_NEUTRAL" value="79"/>
<define name="MAG_X_SENS" value="4.17334785618" integer="16"/>
<define name="MAG_Y_SENS" value="3.98885954135" integer="16"/>
<define name="MAG_Z_SENS" value="4.40442339014" integer="16"/>
<define name="BODY_TO_IMU_PHI" value="0." unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="0." unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="0." unit="deg"/>
</section>
<section name="AHRS" prefix="AHRS_">
<define name="H_X" value="0.3770441"/>
<define name="H_Y" value="0.0193986"/>
<define name="H_Z" value="0.9259921"/>
</section>
<section name="INS" prefix="INS_">
</section>
<section name="STABILIZATION_RATE" prefix="STABILIZATION_RATE_">
<!-- setpoints -->
<define name="SP_MAX_P" value="10000"/>
<define name="SP_MAX_Q" value="10000"/>
<define name="SP_MAX_R" value="10000"/>
<define name="DEADBAND_P" value="20"/>
<define name="DEADBAND_Q" value="20"/>
<define name="DEADBAND_R" value="200"/>
<define name="REF_TAU" value="4"/>
<!-- feedback -->
<define name="GAIN_P" value="400"/>
<define name="GAIN_Q" value="400"/>
<define name="GAIN_R" value="350"/>
<define name="IGAIN_P" value="75"/>
<define name="IGAIN_Q" value="75"/>
<define name="IGAIN_R" value="50"/>
<!-- feedforward -->
<define name="DDGAIN_P" value="300"/>
<define name="DDGAIN_Q" value="300"/>
<define name="DDGAIN_R" value="300"/>
</section>
<section name="STABILIZATION_ATTITUDE" prefix="STABILIZATION_ATTITUDE_">
<!-- setpoints -->
<define name="SP_MAX_PHI" value="45." unit="deg"/>
<define name="SP_MAX_THETA" value="45." unit="deg"/>
<define name="SP_MAX_R" value="90." unit="deg/s"/>
<define name="DEADBAND_A" value="0"/>
<define name="DEADBAND_E" value="0"/>
<define name="DEADBAND_R" value="250"/>
<!-- reference -->
<define name="REF_OMEGA_P" value="400" unit="deg/s"/>
<define name="REF_ZETA_P" value="0.85"/>
<define name="REF_MAX_P" value="400." unit="deg/s"/>
<define name="REF_MAX_PDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_Q" value="400" unit="deg/s"/>
<define name="REF_ZETA_Q" value="0.85"/>
<define name="REF_MAX_Q" value="400." unit="deg/s"/>
<define name="REF_MAX_QDOT" value="RadOfDeg(8000.)"/>
<define name="REF_OMEGA_R" value="250" unit="deg/s"/>
<define name="REF_ZETA_R" value="0.85"/>
<define name="REF_MAX_R" value="180." unit="deg/s"/>
<define name="REF_MAX_RDOT" value="RadOfDeg(1800.)"/>
<!-- feedback -->
<define name="PHI_PGAIN" value="1000"/>
<define name="PHI_DGAIN" value="400"/>
<define name="PHI_IGAIN" value="200"/>
<define name="THETA_PGAIN" value="1000"/>
<define name="THETA_DGAIN" value="400"/>
<define name="THETA_IGAIN" value="200"/>
<define name="PSI_PGAIN" value="500"/>
<define name="PSI_DGAIN" value="300"/>
<define name="PSI_IGAIN" value="10"/>
<!-- feedforward -->
<define name="PHI_DDGAIN" value="300"/>
<define name="THETA_DDGAIN" value="300"/>
<define name="PSI_DDGAIN" value="300"/>
</section>
<section name="GUIDANCE_V" prefix="GUIDANCE_V_">
<define name="HOVER_KP" value="150"/>
<define name="HOVER_KD" value="80"/>
<define name="HOVER_KI" value="20"/>
<!-- NOMINAL_HOVER_THROTTLE sets a fixed value instead of the adaptive estimation -->
<!--define name="NOMINAL_HOVER_THROTTLE" value="0.5"/-->
</section>
<section name="GUIDANCE_H" prefix="GUIDANCE_H_">
<define name="MAX_BANK" value="20" unit="deg"/>
<define name="PGAIN" value="50"/>
<define name="DGAIN" value="100"/>
<define name="AGAIN" value="70"/>
<define name="IGAIN" value="20"/>
</section>
<section name="SIMULATOR" prefix="NPS_">
<define name="ACTUATOR_NAMES" value="{"front_motor", "back_motor", "right_motor", "left_motor"}"/>
<define name="JSBSIM_INIT" value=""reset00""/>
<define name="JSBSIM_MODEL" value=""simple_quad""/>
<define name="SENSORS_PARAMS" value=""nps_sensors_params_default.h""/>
</section>
<section name="AUTOPILOT">
<define name="MODE_MANUAL" value="AP_MODE_ATTITUDE_DIRECT"/>
<define name="MODE_AUTO1" value="AP_MODE_HOVER_Z_HOLD"/>
<define name="MODE_AUTO2" value="AP_MODE_NAV"/>
</section>
<section name="BAT">
<define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="9.6" unit="V"/>
<define name="LOW_BAT_LEVEL" value="9.7" unit="V"/>
<define name="MAX_BAT_LEVEL" value="12.4" unit="V"/>
</section>
</airframe>