Difference between revisions of "Airframe Configuration"
(161 intermediate revisions by 28 users not shown) | |||
Line 1: | Line 1: | ||
<categorytree style="float:right; clear:right; margin-left:1ex; border: 1px solid gray; padding: 0.7ex;" mode=pages>Airframe_Configuration</categorytree> | |||
== | == About == | ||
The airframe file is the most important configuration file and contains all the hardware and software settings for your airframe. It describes what hardware you have and which firmware, sensors, algorithms, etc. you want to use and also holds your configuration parameters. All gains, trims, and behavior settings are defined with standard XML elements. | |||
== | |||
The XML airframe configuration file is located in <tt>conf/airframes/<yourairframe>.xml</tt> and always begins with a <!DOCTYPE airframe SYSTEM "airframe.dtd"> line and should look like this | |||
{{Box Code|conf/airframes/<yourairframe>.xml|<source lang="xml"> | |||
<!DOCTYPE airframe SYSTEM "airframe.dtd"> | |||
<airframe name="yourairframe"> | |||
<!-- The airframe configuration goes here. --> | |||
</airframe> | |||
</source>}} | |||
<b>Also see the wiki pages for [[Fixedwing_Configuration|fixedwing specific configuration]] and [[Rotorcraft_Configuration|rotorcraft specific configuration]].</b> | |||
== Creating a new Aircraft == | |||
While the airframe file is where you configure most aspects of your aircraft, a fully specified aircraft needs several XML configuration files: | |||
* Airframe (what this page is about) | |||
* [[Flight_Plans|Flight Plan]] | |||
* [[Settings]] | |||
* [[Radio_Control|Radio]] (if you use a PPM based R/C system) | |||
* [[Telemetry]] | |||
* [[settings_modules]] | |||
Each aircraft is assigned a name, unique ID and the associated configuration files in [[Conf.xml|<tt>conf/conf.xml</tt>]]. To create a new Aircraft, click new in the menu A/C in the [[Paparazzi_Center|Paparazzi Center]] and select your new airframe file, etc. (or specify it by hand in [[Conf.xml|<tt>conf/conf.xml</tt>]]). | |||
== Firmware and Hardware definitions == | |||
First you should specify which firmware you want to use, that is if you have a <tt>[[Fixedwing_Configuration|fixedwing]]</tt> aircraft or a <tt>[[Rotorcraft_Configuration|rotorcraft]]</tt>: | |||
{{Box Code|conf/airframes/myplane.xml| | |||
<source lang="xml"> | |||
< | <firmware name="fixedwing or rotorcraft"> | ||
< | ... | ||
</firmware> | |||
</source> | |||
}} | |||
=== | === Select your Board === | ||
To specify autopilot hardware you are using and it's low-level settings you have to add a ''target''-tag. | |||
Each ''target'' has two attributes, which are ''name'' and a corresponding ''board'' attribute. | |||
The ''name'' attribute is either "ap" (autopilot) or "sim/jsbsim/nps" (simulation). | |||
{{Box Code|conf/airframes/myplane.xml| | |||
<source lang="xml"> | |||
<firmware name="fixedwing or rotorcraft"> | |||
<target name="sim" board="pc"/> <!-- For simulation. --> | |||
<target name="ap" board="lisa_m_1.0"/> <!-- Select your board here --> | |||
... | |||
</firmware> | |||
</source> | |||
}} | |||
==== Simulation targets ==== | |||
= | target name="sim","jsbsim","nps"<br/> | ||
board="pc"<br/> | |||
More Information at [[Simulation]]. | |||
==== Board targets ==== | |||
== | target name="ap"<br/> | ||
board= | |||
"apogee_0.99", | |||
"apogee_1.0", | |||
"ardrone2", | |||
"booz_1.0", | |||
"classix", | |||
"hb_1.1", | |||
"krooz_sd", | |||
"lisa_l_1.0", | |||
"lisa_l_1.1", | |||
"lisa_m_1.0", | |||
"lisa_m_2.0", | |||
"lisa_mx_2.0", | |||
"lisa_s_0.1", | |||
"logom_2.6", | |||
"navgo_1.0", | |||
"sdlog_1.0", | |||
"stm32f4_discovery", | |||
"tiny_0.99", | |||
"tiny_1.1", | |||
"tiny_2.1", | |||
"tiny_2.11", | |||
"twog_1.0", | |||
"umarim_1.0", | |||
"umarim_lite_2.0", | |||
"yapa_2.0", | |||
All targets can be found in /conf/boards. | |||
=== | ==== Direct Makefile ==== | ||
Optionally you can also add a raw [http://en.wikipedia.org/wiki/Makefile Makefile] section. This is only needed in very advanced setups. For example when testing newly developed hardware. | |||
=== LEDs === | |||
You can configure the LEDs on the autopilot to be used for different status indicators: | |||
; ''SYS_TIME_LED'': blinks with 1Hz | |||
; ''AHRS_ALIGNER_LED'': blinks until the AHRS is aligned (gyro bias initialized) and then stays on | |||
; ''GPS_LED'': blinking if trying to get a fix, on if 3D fix | |||
; ''RADIO_CONTROL_LED'': on if RC signal is ok | |||
; ''BARO_LED'' : only on booz and navgo boards: blinks until baro offset is initialized and then stays on | |||
Depending on your board some of the LEDs on it are already assigned to some indicators by default, check the appropriate autopilot board makefile for the defaults. | |||
To reconfigure the default assignment, assign the indicator to an other value. Use ''none'' if indicator should not be assigned to any LED. | |||
{{Box Code|conf/airframes/myplane.xml| | |||
<source lang="xml"> | |||
<firmware name="fixedwing or rotorcraft"> | |||
... | |||
<configure name="SYS_TIME_LED" value="1"/> | |||
<configure name="RADIO_CONTROL_LED" value="2"/> | |||
<configure name="GPS_LED" value="none"/> | |||
</firmware> | |||
</source> | |||
}} | |||
Beware that you can only assign '''one''' indicator to a LED number. So if the LED you want to use is already in use because another indicator is set to that number by default you have to disable that other indicator by setting it to ''none'' or reconfigure it to an other LED. | |||
== Subsystems == | |||
{| class="wikitable" | |||
|- | |||
| Since '''v5.8''' it is possible to safely replace ''subsystem'' by ''module'' in your airframe file. The roadmap of Paparazzi is to convert existing subsystems to [[modules]]. | |||
|} | |||
Each autopilot features certain [[Subsystems|subsystems]] which need to be configured properly. | |||
The most important ones are described below. | |||
=== IMU === | |||
Add the [[Subsystem/imu|imu subsystem]] with the type you are using. | |||
{{Box Code|conf/airframes/myplane.xml| | |||
<source lang="xml"> | |||
<firmware name="fixedwing or rotorcraft"> | |||
... | |||
<module name="imu" type="aspirin_v1.5"/> | |||
</firmware> | |||
</source> | |||
}} | |||
See the [[Subsystem/imu|imu subsystem]] page for more details. | |||
Also see the [[ImuCalibration|IMU calibration]] page. | |||
=== AHRS === | |||
The [[Subsystem/ahrs|AHRS subsystem]] specifies which attitude estimation filter you are using, e.g. for the complementary filter: | |||
{{Box Code|conf/airframes/myplane.xml| | |||
<source lang="xml"> | |||
<firmware name="fixedwing or rotorcraft"> | |||
... | |||
<module name="ahrs" type="int_cmpl_euler"/> | |||
</firmware> | |||
</source> | |||
}} | |||
All AHRS algorithms depend on an imu subsystem, except for the ahrs_infrared which depends on the infrared module. | |||
See the [[Subsystem/ahrs|AHRS subsystem page]] for more details. | |||
If the magnetometer should be used the [[Subsystem/ahrs#Local_Magnetic_Field|local magnetic field section]] must be filled in. | |||
=== Radio Control === | |||
Supported types are: | |||
* ''ppm'' | |||
* ''spektrum'' | |||
* ''sbus'' | |||
* ''datalink'' | |||
Just specify the appropriate [[Subsystem/radio_control|radio control subsystem]] in your firmware section, e.g.: | |||
{{Box Code|conf/airframes/myplane.xml| | |||
<source lang="xml"> | |||
< | <firmware name="fixedwing or rotorcraft"> | ||
... | |||
< | <module name="radio_control" type="ppm"/> | ||
</firmware> | |||
</source> | |||
}} | |||
=== Telemetry (Modem) === | |||
The modem protocol and baud rate must be set in both the airframe file and ground station. Any standard baud rate can be used, with 9600 being adequate and 57600 recommended for most users to allow high speed telemetry for more detailed flight data analysis. The actual data rate is determined by the number of messages being sent and the period of each message as defined in your [[Telemetry|telemetry file]], e.g. <tt>conf/telemetry/default.xml</tt>. Those wishing to experiment with "alternative" modems can reduce the number and period of each telemetry message to fit within most any bandwidth constraint. | |||
The | The [[Subsystem/telemetry|telemetry subsystem]] supports the following modem protocols: | ||
* Standard transparent serial (pprz) - this is compatible with all modems and can be used to connect the autopilot directly to a PC for testing without a modem. | |||
* Maxstream API protocol (xbee) - compatible with all Maxstream modems including the 9XTend and Zigbee. This protocol enables hardware addressing, allowing multiple aircraft to be managed from a single ground modem. | |||
Just specify the appropriate [[Subsystem/telemetry|telemetry subsystem]] in your firmware section. You can currently choose between the types ''transparent'', ''transparent_usb'' and ''xbee_api''. | |||
'''The default baudrate is 57600 baud, see the [[Subsystem/telemetry|telemetry subsystem]] page for more details and configuration options.''' | |||
{{Box Code|conf/airframes/myplane.xml| | |||
<source lang="xml"> | |||
<firmware name="fixedwing or rotorcraft"> | |||
... | |||
< | <module name="telemetry" type="transparent"/> | ||
</firmware> | |||
</source> | |||
}} | |||
< | |||
=== | === GPS === | ||
The | The serial port settings must match that of the GPS and are configured here along with the necessary files to interpret the u-blox UBX binary protocol: | ||
Just specify the appropriate [[Subsystem/gps|gps subsystem]] in your firmware section. You can currently choose between the types '''ublox''' and '''ublox_utm''' for the older series 4 modules which still provide a UTM message. | |||
{{Box Code|conf/airframes/myplane.xml| | |||
<source lang="xml"> | |||
<firmware name="fixedwing or rotorcraft"> | |||
... | |||
<module name="gps" type="ublox"/> | |||
</firmware> | |||
</source> | |||
}} | |||
The correct UART is already defined by default according to your board. | |||
The default GPS baudrate is 38400baud. | |||
If you need to set different baud rates or UART see the [[Subsystem/gps]] page for the options. | |||
'''Note:''' | |||
* u-blox GPS modules are factory configured for 9600 baud, 38,400 baud is recommended along with the other required changes. The GPS can be accessed directly through the [[tunnel|UART Tunnel]] and [[GPS#GPS_configuration_using_U-Center|Configured with u-center]] | |||
== XML Parameters == | |||
'''When defining parameters you can use [[Units|automatic unit conversion]] to conveniently set it in e.g. degrees.''' | |||
=== Commands === | |||
= | The <b><tt>commands</tt></b> lists the abstract commands you need to control the aircraft. In a simple fixed-wing example, we have only three: | ||
< | <source lang="xml"> | ||
<commands> | |||
< | <axis name="THROTTLE" failsafe_value="0"/> | ||
< | <axis name="ROLL" failsafe_value="0"/> | ||
< | <axis name="PITCH" failsafe_value="0"/> | ||
< | </commands> | ||
</ | </source> | ||
For rotorcraft, it is usually: | |||
<source lang="xml"> | |||
<commands> | |||
<axis name="PITCH" failsafe_value="0"/> | |||
<axis name="ROLL" failsafe_value="0"/> | |||
<axis name="YAW" failsafe_value="0"/> | |||
<axis name="THRUST" failsafe_value="0"/> | |||
</commands> | |||
</source> | |||
Each command is also associated with a failsafe value which will be used if no controller is active, for example during initialization of the autopilot board. The range of these values is [-9600:9600]. For <tt>"THROTTLE"</tt>, the range is [0, 9600] and in the corresponding <b><tt>servo</tt></b> definition the <b><tt>neutral</tt></b> and <b><tt>min</tt></b> are usually the same for PWM based servos (see below). Note that these commands do not necessarily match the servo actuators. For example, the <tt>"ROLL"</tt> command is typically linked to two aileron actuators. | |||
== | === Servos === | ||
The | The above commands get translated to the <b><tt>servos</tt></b> here. In the example below we use two elevons and a motor. ([http://en.wikipedia.org/wiki/Elevon ''Elevons''] are surfaces used for both pitch and roll as on a flying wing.) These servos are listed in the <b><tt>servos</tt></b> section: | ||
<source lang="xml"> | |||
<servos> | |||
<servo name="THROTTLE" no="0" min="1000" neutral="1000" max="2000"/> | |||
< | <servo name="ELEVON_LEFTSIDE" no="1" min="2000" neutral="1500" max="1000"/> | ||
<servo name="ELEVON_RIGHTSIDE" no="2" min="1000" neutral="1500" max="2000"/> | |||
</servos> | |||
</source> | |||
</ | |||
Names are associated to the corresponding '''real physical connector''' to which a servo is connected '''on the autopilot board'''. For example no="2" means connector two on the board. Also the servo neutral value, total range and direction are defined. Min/max/neutral values are expressed in microseconds. The direction of travel can be reversed by exchanging min with max (as in <tt>"ELEVON_LEFTSIDE"</tt>, above). The ''standard'' travel for a hobby servo is 1000µs - 2000µs with a 1500µs neutral. Trim can be added by changing this neutral value. Absolute servo travel limits can be increased or reduced with the min/max values. The <tt>"THROTTLE"</tt> servo typically has the same value for the <b><tt>neutral</tt></b> and <b><tt>min</tt></b>. | |||
The attribute <b><tt>driver</tt></b> for <b><tt>servos</tt></b> node tells which actuators' driver is associated to the listed servos. After the version '''v4.9_devel-164-gdb0d004''', multiple servos sections can be defined and used together, if the correct [[Subsystem/actuators| actuators subsystems]] are loaded. Some boards are automatically loading a default driver, the one used when no <b><tt>driver</tt></b> attribute is specified. | |||
Note the following important tips: | |||
* Reverse the servo direction by exchanging min/max | |||
* Trim should always be adjusted mechanically if possible to avoid asymmetrical travel | |||
* Any reduction of the total travel range should be done mechanically to maintain precision | |||
* Many servos will respond well to values slightly outside the normal 1000-2000µs range but experiment carefully as the servo may not operate reliably outside this range and may even suffer permanent damage. | |||
* Board connector numbering starts with <b>zero (0)</b> not with one | |||
* Servos are also known under the synonym <b>actuators</b> | |||
* (after version '''v4.9_devel-164-gdb0d004''') For I2C based motor speed control using the [[Rotorcraft_Configuration#Motor_Mixing|motor mixing]]: | |||
** min: command to stop the motor | |||
** neutral: motor idle command | |||
** max: max thrust command | |||
The <b><tt>servos</tt></b> are then linked to the commands in the <b><tt>command_laws</tt></b> section: | |||
<source lang="xml"> | |||
<command_laws> | |||
<let var="aileron" value="@ROLL * 0.3"/> | |||
<let var="elevator" value="@PITCH * 0.7"/> | |||
<set servo="THROTTLE" value="@THROTTLE"/> | |||
<set servo="ELEVON_LEFTSIDE" value="$elevator + $aileron"/> | |||
<set servo="ELEVON_RIGHTSIDE" value="$elevator - $aileron"/> | |||
</command_laws> | |||
</source> | |||
[[Image:airframe_sign_conventions.jpg|thumb|Sign conventions for flight dynamics]] | |||
where the third line is the simplest: the throttle servo value equals throttle command value. The other lines define and control the pitch/roll mixing. Elevon values are computed with a combination of two commands, '''ROLL''' and '''PITCH'''. This ''mixer'' is defined with two intermediate variables '''aileron''' and '''elevator''' introduced with the <b><tt>let</tt></b> element. The '''@''' symbol is used to reference a command value in the <b><tt>value</tt></b> attribute of the <b><tt>set</tt></b> and <b><tt>let</tt></b> elements. In the above example, the servos are limited to +/- 70% of their full travel for pitch and 30% for roll, only in combination can the servos reach 100% deflection. Note that these numbers ''should add up 100% or more, never less''. For example, you may want 100% travel available for pitch - this means if a roll is commanded along with maximum pitch only one servo will respond to the roll command as the other has already reached its mechanical limit. If you find after tuning that these numbers add to less than 100% consider reducing the surface travel mechanically. | |||
Note that the signs used in the description follow the standard convention. | |||
After '''v4.9_devel-164-gdb0d004''', the <b><tt>command_laws</tt></b> section is mandatory for both fixedwing and rotorcraft firmwares, only for fixedwing otherwise. | |||
=== Battery === | |||
This section gives characteristics for monitoring the main power battery. | |||
For | <b><tt>MILLIAMP_AT_FULL_THROTTLE</tt></b> represents the actual current (in mA) when full THROTTLE is applied. Note that when flying the current typically is significantly lower than in static tests at home on your workbench. <b><tt>MILLIAMP_AT_FULL_THROTTLE</tt></b> is used to compute the <tt>energy</tt> value of the <tt>BAT</tt> message when no [[Current_sensor|Current sensor]] is mounted in the airframe. This value can also be used in flight plans. For example, if at full throttle your motor consumes 10 Amps, use a value of 10000. You can "tweak" this number after a few flights to match the capacity of your battery. If upon landing your bat.energy messages says that you used 2500 mAh while the energy recharged into the battery is only 2000 mAh, you could reduce the <b><tt>MILLIAMP_AT_FULL_THROTTLE</tt></b> value by 20% to match your in-flight current consumption. This tweaking is most precise if you fly full throttle only (respectively no throttle to glide down again). | ||
The <b><tt>CURRENT_ESTIMATION_NONLINEARITY</tt></b> can be added to tweak the energy estimation for non full throttle cruise. As the current consumption is nonlinear, at 50% throttle it is likely to be substantially less than 50%. A superellipse is used to approximate this nonlinearity. The default setting is 1.2 and is used if the <b><tt>CURRENT_ESTIMATION_NONLINEARITY</tt></b> is not defined in your airframe file. A value 1 corresponds to linear behaviour, 1.5 corresponds to strong nonlinearity. The tweaking is done same as described above for <b><tt>MILLIAMP_AT_FULL_THROTTLE</tt></b>, but only partial throttle (cruise throttle) should be applied in flight. | |||
If both <b><tt>MILLIAMP_AT_FULL_THROTTLE</tt></b> and <b><tt>CURRENT_ESTIMATION_NONLINEARITY</tt></b> are tweaked well, you get precise energy estimations with less than 5% error independent of your flight pattern without even requiring a [[Current_sensor|current sensor]]. | |||
The <b><tt>CATASTROPHIC_BAT_LEVEL</tt></b> (was previously <b><tt>LOW_BATTERY</tt></b>) value defines the voltage at which the autopilot will lock the throttle at 0% in autonomous mode (kill_throttle mode). This value is also used by the ground server to issue a '''CATASTROPHIC''' alarm message on the bus (this message will be displayed in the console of the GCS). <b><tt>CRITIC</tt></b> and <b><tt>LOW</tt></b> values will also used as threshold for '''CRITIC''' and '''WARNING''' alarms. They are optional and the respective defaults are 10.0 and 10.5V. | |||
The | |||
The <b><tt>MAX_BAT_LEVEL</tt></b> may be specified to improve the display of the battery gauge in the strip or in "papgets". Note that this definition is optional, with a default value of 12.5V. | |||
{{Box Code|conf/airframes/myplane.xml| | {{Box Code|conf/airframes/myplane.xml| | ||
<source lang="xml"> | |||
<firmware name="fixedwing"> | |||
<define name=" | ... | ||
<define name=" | <define name="ADC_CHANNEL_VSUPPLY" value="ADC_4" /> | ||
</firmware> | |||
... | |||
<section name="BAT"> | |||
<define name="MILLIAMP_AT_FULL_THROTTLE" value="12000" unit="mA" /> | |||
<define name="CATASTROPHIC_BAT_LEVEL" value="6.0" unit="V"/> | |||
<define name="CRITIC_BAT_LEVEL" value="6.5" unit="V"/> | |||
<define name="LOW_BAT_LEVEL" value="7.0" unit="V"/> | |||
<define name="MAX_BAT_LEVEL" value="8.4" unit="V"/> | |||
</section> | </section> | ||
</ | </source> | ||
}} | }} | ||
{{Box Code|conf/airframes/myplane.xml | The conversion of ADC measurements to Voltage is already defined for the different autopilot boards, if you need to override these defaults you can use the <b><tt>VoltageOfAdc(adc)</tt></b> define and also specify offsets or anything else you might need, e.g.: | ||
{{Box Code|conf/airframes/myplane.xml| | |||
<source lang="xml"> | |||
<section name="BAT"> | |||
... | |||
<define name="VOLTAGE_ADC_SCALE" value="0.0177531"/> | |||
<define name="VOLTAGE_OFFSET" value="0.5" unit="V"/> | |||
<define name="VoltageOfAdc(adc)" value="(VOLTAGE_ADC_SCALE * adc + VOLTAGE_OFFSET)"/> | |||
</section> | |||
</source> | |||
}} | }} | ||
Calculating '''VOLTAGE_ADC_SCALE''': | |||
<math>VOLTAGE\_ADC\_SCALE=\frac{Vref}{ADCresolution-1}\div\frac{R2}{R1+R2}</math> | |||
*Vref - Voltage reference for the ADC (will be 3.3V in most cases, can be found in mcu/adc datasheet) | |||
*ADCresolution - ADC bit depth (e.g. 2^12=4096 for a 12 bit ADC) | |||
*R1 - Resistor between battery and ADC input pin of MCU | |||
*R2 - Resistor between ADC input pin of the MCU and GND | |||
It is also a good idea to measure the actual voltage of the battery with a precision voltage meter, compare it with the calculated value from the autopilot (e.g. via [[Paparazzi_Center#Messages]]) and edit the vales for ADC scaling. Since the resistors have a tolerance, this can fine tune the measurement. | |||
=== Modules === | |||
</ | The [[Modules|modules]] allow to add new code in a flexible way with initialisation, periodic and event functions without modifying the main AP loop. | ||
<source lang="xml"> | |||
<modules main_freq="60"> | |||
<load name="demo_module.xml"/> | |||
</modules> | |||
</source> | |||
* The main_freq parameter (in Hz) allows to specify the frequency of the main loop. Default is 60 Hz | |||
{ | {| class="wikitable" | ||
|- | |||
| Since '''v5.8''' it is possible to safely replace ''subsystem'' by ''module'' in your airframe file. It is therefore also possible to use the modules the same way subsystems used to be (i.e. as children of the ''firmware'' node and not only the ''modules'' node as presented above. The roadmap of Paparazzi is to convert existing subsystems to [[modules]]. | |||
|} | |||
< | {| class="wikitable" | ||
|- | |||
| Starting from '''v5.12''' the ''modules'' element will gradually be phased out. Instead, the modules should be added inside the ''firmware'' tags of the airframe file: | |||
|} | |||
<source lang="xml> | |||
<firmware name="fixedwing or rotorcraft"> | |||
... | |||
<module name="demo_module"/> | |||
</firmware> | |||
</source> | |||
Additional modules can also be added from the [[Flight Plans#Modules|flight plan]]. | |||
=== GCS === | |||
[[Image:ac_icon_multi_uav.png|thumb|Various A/C icons demonstrated on a multi UAV simulation session]] | |||
[[Image:Icons_Theme_Default.png|thumb|Default Theme]] | |||
[[Image:Icons_Theme_Flat.png|thumb|Flat Theme]] | |||
Use this <b>optional</b> section to help customize parts of the GCS for a specific airframe: | |||
{{Box Code|conf/airframes/myplane.xml| | {{Box Code|conf/airframes/myplane.xml| | ||
<source lang="xml"> | |||
<section name="GCS"> | |||
... | |||
<define name="ICONS_THEME" value="flat_theme"/> | |||
<define name="ALT_SHIFT_PLUS_PLUS" value="30"/> | |||
<define name="ALT_SHIFT_PLUS" value="5"/> | |||
<define name="ALT_SHIFT_MINUS" value="-5"/> | |||
<define name="SPEECH_NAME" value="Quad"/> | |||
<define name="AC_ICON" value="flyingwing"/> | |||
</section> | |||
</source> | |||
}} | }} | ||
* <tt>ICONS_THEME</tt> can be used to define an alternate/custom GCS icons theme for a given aircraft The '''flat_theme''' is one example of an alternate set of GCS icons. | |||
* <tt>ALT_SHIFT_PLUS_PLUS</tt> sets the number of metres the target altitude will change when the double up arrow button is pressed on the [[GCS#Strips|strip]] | |||
* <tt>ALT_SHIFT_PLUS</tt> sets the number of metres the target altitude will change when the up arrow button is pressed on the [[GCS#Strips|strip]] | |||
* <tt>ALT_SHIFT_MINUS</tt> sets the number of metres the target altitude will change when the down arrow button is pressed on the [[GCS#Strips|strip]] | |||
* <tt>SPEECH_NAME</tt> a string ([a-zA-Z0-9_]) that will be used in place of the aircraft name specified in <tt>conf.xml</tt> for the [[Speech|speech]] and [[GCS#Alarms|alarms]] functionality. Set this to "_" to prevent the speech function from saying the aircraft name. Useful if your aircraft name takes a long time to say (i.e. "UAV1-A_with_spektrum" can be shortened to "Plane"). | |||
* <tt>AC_ICON</tt> can be used to define the vehicle icon (or overwrite the default icon) that shows up on the 2D-map of the GCS. Available values are: <tt>flyingwing</tt> , <tt>fixedwing</tt> , <tt>rotorcraft</tt> , <tt>quadrotor</tt> , <tt>hexarotor</tt> , <tt>octorotor</tt> , <tt>quadrotor_x</tt> , <tt>hexarotor_x</tt> , <tt>octorotor_x</tt> , <tt>home</tt>. | |||
==== Custom Icons Theme Support ==== | |||
A custom icons theme is supported through the use of the '''ICONS_THEME''' attribute. Set the '''ICONS_THEME''' attribute ''value'' to the path of your custom icons theme directory and the given aircraft will now display your custom icons. Note that the path is relative to the default GCS icons path root: ''$PAPARAZZI_HOME/data/pictures/gcs_icons'' | |||
{{Box Code| | {{Box Code|code snippet| | ||
<source lang="xml"> | |||
<section name="GCS"> | |||
<define name="ICONS_THEME" value="myawesome_icons"/> | |||
</section> | |||
</source> | |||
}} | }} | ||
The directory that contains your custom icons, in this example named ''myawesome_icons'', is located at ''$PAPARAZZI_HOME/data/pictures/gcs_icons''. | |||
[[Category:User_Documentation]] [[Category:Airframe_Configuration]] | |||
Latest revision as of 06:34, 24 September 2018
About
The airframe file is the most important configuration file and contains all the hardware and software settings for your airframe. It describes what hardware you have and which firmware, sensors, algorithms, etc. you want to use and also holds your configuration parameters. All gains, trims, and behavior settings are defined with standard XML elements.
The XML airframe configuration file is located in conf/airframes/<yourairframe>.xml and always begins with a <!DOCTYPE airframe SYSTEM "airframe.dtd"> line and should look like this
File: conf/airframes/<yourairframe>.xml |
<!DOCTYPE airframe SYSTEM "airframe.dtd">
<airframe name="yourairframe">
<!-- The airframe configuration goes here. -->
</airframe>
|
Also see the wiki pages for fixedwing specific configuration and rotorcraft specific configuration.
Creating a new Aircraft
While the airframe file is where you configure most aspects of your aircraft, a fully specified aircraft needs several XML configuration files:
- Airframe (what this page is about)
- Flight Plan
- Settings
- Radio (if you use a PPM based R/C system)
- Telemetry
- settings_modules
Each aircraft is assigned a name, unique ID and the associated configuration files in conf/conf.xml. To create a new Aircraft, click new in the menu A/C in the Paparazzi Center and select your new airframe file, etc. (or specify it by hand in conf/conf.xml).
Firmware and Hardware definitions
First you should specify which firmware you want to use, that is if you have a fixedwing aircraft or a rotorcraft:
File: conf/airframes/myplane.xml |
<firmware name="fixedwing or rotorcraft">
...
</firmware>
|
Select your Board
To specify autopilot hardware you are using and it's low-level settings you have to add a target-tag. Each target has two attributes, which are name and a corresponding board attribute. The name attribute is either "ap" (autopilot) or "sim/jsbsim/nps" (simulation).
File: conf/airframes/myplane.xml |
<firmware name="fixedwing or rotorcraft">
<target name="sim" board="pc"/> <!-- For simulation. -->
<target name="ap" board="lisa_m_1.0"/> <!-- Select your board here -->
...
</firmware>
|
Simulation targets
target name="sim","jsbsim","nps"
board="pc"
More Information at Simulation.
Board targets
target name="ap"
board=
"apogee_0.99",
"apogee_1.0",
"ardrone2",
"booz_1.0",
"classix",
"hb_1.1",
"krooz_sd",
"lisa_l_1.0",
"lisa_l_1.1",
"lisa_m_1.0",
"lisa_m_2.0",
"lisa_mx_2.0",
"lisa_s_0.1",
"logom_2.6",
"navgo_1.0",
"sdlog_1.0",
"stm32f4_discovery",
"tiny_0.99",
"tiny_1.1",
"tiny_2.1",
"tiny_2.11",
"twog_1.0",
"umarim_1.0",
"umarim_lite_2.0",
"yapa_2.0",
All targets can be found in /conf/boards.
Direct Makefile
Optionally you can also add a raw Makefile section. This is only needed in very advanced setups. For example when testing newly developed hardware.
LEDs
You can configure the LEDs on the autopilot to be used for different status indicators:
- SYS_TIME_LED
- blinks with 1Hz
- AHRS_ALIGNER_LED
- blinks until the AHRS is aligned (gyro bias initialized) and then stays on
- GPS_LED
- blinking if trying to get a fix, on if 3D fix
- RADIO_CONTROL_LED
- on if RC signal is ok
- BARO_LED
- only on booz and navgo boards: blinks until baro offset is initialized and then stays on
Depending on your board some of the LEDs on it are already assigned to some indicators by default, check the appropriate autopilot board makefile for the defaults.
To reconfigure the default assignment, assign the indicator to an other value. Use none if indicator should not be assigned to any LED.
File: conf/airframes/myplane.xml |
<firmware name="fixedwing or rotorcraft">
...
<configure name="SYS_TIME_LED" value="1"/>
<configure name="RADIO_CONTROL_LED" value="2"/>
<configure name="GPS_LED" value="none"/>
</firmware>
|
Beware that you can only assign one indicator to a LED number. So if the LED you want to use is already in use because another indicator is set to that number by default you have to disable that other indicator by setting it to none or reconfigure it to an other LED.
Subsystems
Since v5.8 it is possible to safely replace subsystem by module in your airframe file. The roadmap of Paparazzi is to convert existing subsystems to modules. |
Each autopilot features certain subsystems which need to be configured properly. The most important ones are described below.
IMU
Add the imu subsystem with the type you are using.
File: conf/airframes/myplane.xml |
<firmware name="fixedwing or rotorcraft">
...
<module name="imu" type="aspirin_v1.5"/>
</firmware>
|
See the imu subsystem page for more details. Also see the IMU calibration page.
AHRS
The AHRS subsystem specifies which attitude estimation filter you are using, e.g. for the complementary filter:
File: conf/airframes/myplane.xml |
<firmware name="fixedwing or rotorcraft">
...
<module name="ahrs" type="int_cmpl_euler"/>
</firmware>
|
All AHRS algorithms depend on an imu subsystem, except for the ahrs_infrared which depends on the infrared module. See the AHRS subsystem page for more details.
If the magnetometer should be used the local magnetic field section must be filled in.
Radio Control
Supported types are:
- ppm
- spektrum
- sbus
- datalink
Just specify the appropriate radio control subsystem in your firmware section, e.g.:
File: conf/airframes/myplane.xml |
<firmware name="fixedwing or rotorcraft">
...
<module name="radio_control" type="ppm"/>
</firmware>
|
Telemetry (Modem)
The modem protocol and baud rate must be set in both the airframe file and ground station. Any standard baud rate can be used, with 9600 being adequate and 57600 recommended for most users to allow high speed telemetry for more detailed flight data analysis. The actual data rate is determined by the number of messages being sent and the period of each message as defined in your telemetry file, e.g. conf/telemetry/default.xml. Those wishing to experiment with "alternative" modems can reduce the number and period of each telemetry message to fit within most any bandwidth constraint.
The telemetry subsystem supports the following modem protocols:
- Standard transparent serial (pprz) - this is compatible with all modems and can be used to connect the autopilot directly to a PC for testing without a modem.
- Maxstream API protocol (xbee) - compatible with all Maxstream modems including the 9XTend and Zigbee. This protocol enables hardware addressing, allowing multiple aircraft to be managed from a single ground modem.
Just specify the appropriate telemetry subsystem in your firmware section. You can currently choose between the types transparent, transparent_usb and xbee_api.
The default baudrate is 57600 baud, see the telemetry subsystem page for more details and configuration options.
File: conf/airframes/myplane.xml |
<firmware name="fixedwing or rotorcraft">
...
<module name="telemetry" type="transparent"/>
</firmware>
|
GPS
The serial port settings must match that of the GPS and are configured here along with the necessary files to interpret the u-blox UBX binary protocol:
Just specify the appropriate gps subsystem in your firmware section. You can currently choose between the types ublox and ublox_utm for the older series 4 modules which still provide a UTM message.
File: conf/airframes/myplane.xml |
<firmware name="fixedwing or rotorcraft">
...
<module name="gps" type="ublox"/>
</firmware>
|
The correct UART is already defined by default according to your board. The default GPS baudrate is 38400baud.
If you need to set different baud rates or UART see the Subsystem/gps page for the options.
Note:
- u-blox GPS modules are factory configured for 9600 baud, 38,400 baud is recommended along with the other required changes. The GPS can be accessed directly through the UART Tunnel and Configured with u-center
XML Parameters
When defining parameters you can use automatic unit conversion to conveniently set it in e.g. degrees.
Commands
The commands lists the abstract commands you need to control the aircraft. In a simple fixed-wing example, we have only three:
<commands>
<axis name="THROTTLE" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="PITCH" failsafe_value="0"/>
</commands>
For rotorcraft, it is usually:
<commands>
<axis name="PITCH" failsafe_value="0"/>
<axis name="ROLL" failsafe_value="0"/>
<axis name="YAW" failsafe_value="0"/>
<axis name="THRUST" failsafe_value="0"/>
</commands>
Each command is also associated with a failsafe value which will be used if no controller is active, for example during initialization of the autopilot board. The range of these values is [-9600:9600]. For "THROTTLE", the range is [0, 9600] and in the corresponding servo definition the neutral and min are usually the same for PWM based servos (see below). Note that these commands do not necessarily match the servo actuators. For example, the "ROLL" command is typically linked to two aileron actuators.
Servos
The above commands get translated to the servos here. In the example below we use two elevons and a motor. (Elevons are surfaces used for both pitch and roll as on a flying wing.) These servos are listed in the servos section:
<servos>
<servo name="THROTTLE" no="0" min="1000" neutral="1000" max="2000"/>
<servo name="ELEVON_LEFTSIDE" no="1" min="2000" neutral="1500" max="1000"/>
<servo name="ELEVON_RIGHTSIDE" no="2" min="1000" neutral="1500" max="2000"/>
</servos>
Names are associated to the corresponding real physical connector to which a servo is connected on the autopilot board. For example no="2" means connector two on the board. Also the servo neutral value, total range and direction are defined. Min/max/neutral values are expressed in microseconds. The direction of travel can be reversed by exchanging min with max (as in "ELEVON_LEFTSIDE", above). The standard travel for a hobby servo is 1000µs - 2000µs with a 1500µs neutral. Trim can be added by changing this neutral value. Absolute servo travel limits can be increased or reduced with the min/max values. The "THROTTLE" servo typically has the same value for the neutral and min.
The attribute driver for servos node tells which actuators' driver is associated to the listed servos. After the version v4.9_devel-164-gdb0d004, multiple servos sections can be defined and used together, if the correct actuators subsystems are loaded. Some boards are automatically loading a default driver, the one used when no driver attribute is specified.
Note the following important tips:
- Reverse the servo direction by exchanging min/max
- Trim should always be adjusted mechanically if possible to avoid asymmetrical travel
- Any reduction of the total travel range should be done mechanically to maintain precision
- Many servos will respond well to values slightly outside the normal 1000-2000µs range but experiment carefully as the servo may not operate reliably outside this range and may even suffer permanent damage.
- Board connector numbering starts with zero (0) not with one
- Servos are also known under the synonym actuators
- (after version v4.9_devel-164-gdb0d004) For I2C based motor speed control using the motor mixing:
- min: command to stop the motor
- neutral: motor idle command
- max: max thrust command
The servos are then linked to the commands in the command_laws section:
<command_laws>
<let var="aileron" value="@ROLL * 0.3"/>
<let var="elevator" value="@PITCH * 0.7"/>
<set servo="THROTTLE" value="@THROTTLE"/>
<set servo="ELEVON_LEFTSIDE" value="$elevator + $aileron"/>
<set servo="ELEVON_RIGHTSIDE" value="$elevator - $aileron"/>
</command_laws>
where the third line is the simplest: the throttle servo value equals throttle command value. The other lines define and control the pitch/roll mixing. Elevon values are computed with a combination of two commands, ROLL and PITCH. This mixer is defined with two intermediate variables aileron and elevator introduced with the let element. The @ symbol is used to reference a command value in the value attribute of the set and let elements. In the above example, the servos are limited to +/- 70% of their full travel for pitch and 30% for roll, only in combination can the servos reach 100% deflection. Note that these numbers should add up 100% or more, never less. For example, you may want 100% travel available for pitch - this means if a roll is commanded along with maximum pitch only one servo will respond to the roll command as the other has already reached its mechanical limit. If you find after tuning that these numbers add to less than 100% consider reducing the surface travel mechanically.
Note that the signs used in the description follow the standard convention.
After v4.9_devel-164-gdb0d004, the command_laws section is mandatory for both fixedwing and rotorcraft firmwares, only for fixedwing otherwise.
Battery
This section gives characteristics for monitoring the main power battery.
MILLIAMP_AT_FULL_THROTTLE represents the actual current (in mA) when full THROTTLE is applied. Note that when flying the current typically is significantly lower than in static tests at home on your workbench. MILLIAMP_AT_FULL_THROTTLE is used to compute the energy value of the BAT message when no Current sensor is mounted in the airframe. This value can also be used in flight plans. For example, if at full throttle your motor consumes 10 Amps, use a value of 10000. You can "tweak" this number after a few flights to match the capacity of your battery. If upon landing your bat.energy messages says that you used 2500 mAh while the energy recharged into the battery is only 2000 mAh, you could reduce the MILLIAMP_AT_FULL_THROTTLE value by 20% to match your in-flight current consumption. This tweaking is most precise if you fly full throttle only (respectively no throttle to glide down again).
The CURRENT_ESTIMATION_NONLINEARITY can be added to tweak the energy estimation for non full throttle cruise. As the current consumption is nonlinear, at 50% throttle it is likely to be substantially less than 50%. A superellipse is used to approximate this nonlinearity. The default setting is 1.2 and is used if the CURRENT_ESTIMATION_NONLINEARITY is not defined in your airframe file. A value 1 corresponds to linear behaviour, 1.5 corresponds to strong nonlinearity. The tweaking is done same as described above for MILLIAMP_AT_FULL_THROTTLE, but only partial throttle (cruise throttle) should be applied in flight.
If both MILLIAMP_AT_FULL_THROTTLE and CURRENT_ESTIMATION_NONLINEARITY are tweaked well, you get precise energy estimations with less than 5% error independent of your flight pattern without even requiring a current sensor.
The CATASTROPHIC_BAT_LEVEL (was previously LOW_BATTERY) value defines the voltage at which the autopilot will lock the throttle at 0% in autonomous mode (kill_throttle mode). This value is also used by the ground server to issue a CATASTROPHIC alarm message on the bus (this message will be displayed in the console of the GCS). CRITIC and LOW values will also used as threshold for CRITIC and WARNING alarms. They are optional and the respective defaults are 10.0 and 10.5V.
The MAX_BAT_LEVEL may be specified to improve the display of the battery gauge in the strip or in "papgets". Note that this definition is optional, with a default value of 12.5V.
File: conf/airframes/myplane.xml |
<firmware name="fixedwing">
...
<define name="ADC_CHANNEL_VSUPPLY" value="ADC_4" />
</firmware>
...
<section name="BAT">
<define name="MILLIAMP_AT_FULL_THROTTLE" value="12000" unit="mA" />
<define name="CATASTROPHIC_BAT_LEVEL" value="6.0" unit="V"/>
<define name="CRITIC_BAT_LEVEL" value="6.5" unit="V"/>
<define name="LOW_BAT_LEVEL" value="7.0" unit="V"/>
<define name="MAX_BAT_LEVEL" value="8.4" unit="V"/>
</section>
|
The conversion of ADC measurements to Voltage is already defined for the different autopilot boards, if you need to override these defaults you can use the VoltageOfAdc(adc) define and also specify offsets or anything else you might need, e.g.:
File: conf/airframes/myplane.xml |
<section name="BAT">
...
<define name="VOLTAGE_ADC_SCALE" value="0.0177531"/>
<define name="VOLTAGE_OFFSET" value="0.5" unit="V"/>
<define name="VoltageOfAdc(adc)" value="(VOLTAGE_ADC_SCALE * adc + VOLTAGE_OFFSET)"/>
</section>
|
Calculating VOLTAGE_ADC_SCALE:
- Vref - Voltage reference for the ADC (will be 3.3V in most cases, can be found in mcu/adc datasheet)
- ADCresolution - ADC bit depth (e.g. 2^12=4096 for a 12 bit ADC)
- R1 - Resistor between battery and ADC input pin of MCU
- R2 - Resistor between ADC input pin of the MCU and GND
It is also a good idea to measure the actual voltage of the battery with a precision voltage meter, compare it with the calculated value from the autopilot (e.g. via Paparazzi_Center#Messages) and edit the vales for ADC scaling. Since the resistors have a tolerance, this can fine tune the measurement.
Modules
The modules allow to add new code in a flexible way with initialisation, periodic and event functions without modifying the main AP loop.
<modules main_freq="60">
<load name="demo_module.xml"/>
</modules>
- The main_freq parameter (in Hz) allows to specify the frequency of the main loop. Default is 60 Hz
Since v5.8 it is possible to safely replace subsystem by module in your airframe file. It is therefore also possible to use the modules the same way subsystems used to be (i.e. as children of the firmware node and not only the modules node as presented above. The roadmap of Paparazzi is to convert existing subsystems to modules. |
Starting from v5.12 the modules element will gradually be phased out. Instead, the modules should be added inside the firmware tags of the airframe file: |
<firmware name="fixedwing or rotorcraft">
...
<module name="demo_module"/>
</firmware>
Additional modules can also be added from the flight plan.
GCS
Use this optional section to help customize parts of the GCS for a specific airframe:
File: conf/airframes/myplane.xml |
<section name="GCS">
...
<define name="ICONS_THEME" value="flat_theme"/>
<define name="ALT_SHIFT_PLUS_PLUS" value="30"/>
<define name="ALT_SHIFT_PLUS" value="5"/>
<define name="ALT_SHIFT_MINUS" value="-5"/>
<define name="SPEECH_NAME" value="Quad"/>
<define name="AC_ICON" value="flyingwing"/>
</section>
|
- ICONS_THEME can be used to define an alternate/custom GCS icons theme for a given aircraft The flat_theme is one example of an alternate set of GCS icons.
- ALT_SHIFT_PLUS_PLUS sets the number of metres the target altitude will change when the double up arrow button is pressed on the strip
- ALT_SHIFT_PLUS sets the number of metres the target altitude will change when the up arrow button is pressed on the strip
- ALT_SHIFT_MINUS sets the number of metres the target altitude will change when the down arrow button is pressed on the strip
- SPEECH_NAME a string ([a-zA-Z0-9_]) that will be used in place of the aircraft name specified in conf.xml for the speech and alarms functionality. Set this to "_" to prevent the speech function from saying the aircraft name. Useful if your aircraft name takes a long time to say (i.e. "UAV1-A_with_spektrum" can be shortened to "Plane").
- AC_ICON can be used to define the vehicle icon (or overwrite the default icon) that shows up on the 2D-map of the GCS. Available values are: flyingwing , fixedwing , rotorcraft , quadrotor , hexarotor , octorotor , quadrotor_x , hexarotor_x , octorotor_x , home.
Custom Icons Theme Support
A custom icons theme is supported through the use of the ICONS_THEME attribute. Set the ICONS_THEME attribute value to the path of your custom icons theme directory and the given aircraft will now display your custom icons. Note that the path is relative to the default GCS icons path root: $PAPARAZZI_HOME/data/pictures/gcs_icons
File: code snippet |
<section name="GCS">
<define name="ICONS_THEME" value="myawesome_icons"/>
</section>
|
The directory that contains your custom icons, in this example named myawesome_icons, is located at $PAPARAZZI_HOME/data/pictures/gcs_icons.