Rotorcraft Configuration

From PaparazziUAV
Revision as of 12:47, 3 August 2011 by Audax (talk | contribs)
Jump to navigation Jump to search

The airframe configuration file is located in conf/airframes and contains all the hardware and software settings for an aircraft. All gains, trims, and behavior settings are defined with standard XML elements. Optionally you can also add a raw Makefile section.

Autopilot modes

For rotorcrafts we have a lot of different modes that can be mapped to your 3-position switch (Manual, Auto1, Auto2). The horizontal and vertical mode can be set differently as the following possible modes indicate:

AP_MODE_FAILSAFE

This is a failsafe mode that gets triggered if:

  • RC signal is lost (and you are not in KILL or NAV mode)
  • GPS and RC is lost in NAV mode

The autopilot will level the rotorcraft out (setpoints to zero pitch and roll angles) and descend at 0.5m/s downwards.

AP_MODE_KILL

Motors are simply switched off.

AP_MODE_RATE_DIRECT

This is basically the "most" manual mode you can get. You control not the attitude (roll and pitch angles) but the rotation rate. You also set the throttle directly with your RC.

AP_MODE_ATTITUDE_DIRECT

You control the attitude (roll, pitch and yaw angles), but the throttle directly proportional to your stick position.

AP_MODE_RATE_RC_CLIMB

You control the rotation rate and the vertical speed according to your throttle stick position. If you have your throttle stick in the middle position, the altitude is keept, down goes down at a speed proportional to your stick position (same for up). In this mode it makes sense to mount the spring for your throttle stick so it recenter itself.

AP_MODE_ATTITUDE_RC_CLIMB

You control the attitude (roll, pitch and yaw angles) and the vertical speed according to your throttle stick position. If you have your throttle stick in the middle position, the altitude is keept, down goes down at a speed proportional to your stick position (same for up). In this mode it makes sense to mount the spring for your throttle stick so it recenter itself.

AP_MODE_ATTITUDE_CLIMB

You control the attitude (roll, pitch and yaw angles) and the vertical speed. The vertical speed is set via fms (e.g. joystick).

AP_MODE_RATE_Z_HOLD

You control the rotation rate and it holds the altitude you were at when entering this mode. Your throttle stick position still limits the max throttle authority, so you should push your throttle stick up after entering this mode so the vertical controller has some "room" to stabilize the altitude. Should something weird happen you can limit the max thrust by taking throttle back.

AP_MODE_ATTITUDE_Z_HOLD

You control the attitude (roll, pitch and yaw angles) and it holds the altitude you were at when entering this mode. Your throttle stick position still limits the max throttle authority, so you should push your throttle stick up after entering this mode so the vertical controller has some "room" to stabilize the altitude. Should something weird happen you can limit the max thrust by taking throttle back.

AP_MODE_HOVER_DIRECT

The rotorcraft hovers at the horizontal position you were at when entering this mode (position control). You still set the throttle directly with your RC.

AP_MODE_HOVER_CLIMB

The rotorcraft hovers at the position you were at when entering this mode (position control). The vertical speed is set via fms (e.g. joystick).

AP_MODE_HOVER_Z_HOLD

The rotorcraft hovers at the 3D position you were at when entering this mode (position and altitude control). Your throttle stick position still limits the max throttle authority, so you should push your throttle stick up after entering this mode so the vertical controller has some "room" to stabilize the altitude. Should something weird happen you can limit the max thrust by taking throttle back.

AP_MODE_NAV

Full navigation mode. The rotorcraft follows your flightplan.

Control Loops

The control loops for rotorcraft can be found in Control Loops.

XML Parameters

Mode

In the mode section you can set the autopilot modes associated with your 3-way mode switch on your RC.

<section name="MODE" prefix="MODE_">
  <define name="MANUAL" value="AP_MODE_ATTITUDE_DIRECT" />
  <define name="AUTO1" value="AP_MODE_ATTITUDE_Z_HOLD" />
  <define name="AUTO2" value="AP_MODE_HOVER_Z_HOLD" />
</section>

Commands

The commands lists the abstract commands you need to control the aircraft. For most multicopter you just need:

<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.

Supervision

This section describes the "mixing" used for your particular multirotor configuration. This section is needed for "mkk" (mikrokopter) and "asctecV2" controllers, as "asctecV1" do their mixing themselves.

   <section name="SUPERVISION" prefix="SUPERVISION_">
    <define name="MIN_MOTOR" value="3"/>
    <define name="MAX_MOTOR" value="200"/>
    <define name="TRIM_A" value="0"/>
    <define name="TRIM_E" value="0"/>
    <define name="TRIM_R" value="0"/>
    <define name="NB_MOTOR" value="4"/>
    <define name="SCALE" value="256"/>
    <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>

Below are values for the common "plus cross", "time cross" quadrirotor configurations.


Plus Cross
Cross plus simple.png

Assuming that the order of motors, described in the "servos" section is FRONT, BACK, LEFT, RIGHT.

    <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 }"/>


Time Cross
Cross time simple.png

Assuming that the order of motors, described in the "servos" section is NE, SE, SW, NW.

    <define name="ROLL_COEF"   value="{ -256, -256,  256,  256 }"/>
    <define name="PITCH_COEF"  value="{  256, -256, -256,  256 }"/>
    <define name="YAW_COEF"    value="{  256, -256,  256, -256 }"/>
    <define name="THRUST_COEF" value="{  256,  256,  256,  256 }"/>

if your rotors are spinning opposite to the direction showed in the picture, just reverse signs in the YAW_COEF line.

If you want to compute mixing for a special configuration, please see the RotorcraftMixing page.

Bat

This section give characteristics for the monitoring of the main power battery.

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.

<section name="BAT">
  <define name="MILLIAMP_PER_PERCENT" value="0.86" />
  <define name="CATASTROPHIC_BAT_LEVEL" value="9.3" unit="V" />
  <define name="MAX_BAT_LEVEL" value="12.0" unit="V" />
  <define name="BATTERY_SENS" value="0.246" integer="16" />
  <define name="BATTERY_OFFSET" value="0" />
</section>


Simulation

Values from this section can be used to tweak the SITL simulation. The NPS (New Paparazzi Sim) currently uses JSBSim as for the flight dynamic modeling, but other FDMs are possible.

<section name="SIMULATOR" prefix="NPS_">
  <define name="ACTUATOR_NAMES" value="{"front_motor", "back_motor", "right_motor", "left_motor"}" />
  <define name="INITIAL_CONDITITONS" value=""reset00"" />
  <define name="SENSORS_PARAMS" value=""nps_sensors_params_booz2_a1.h"" />
</section>

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="512">
 <load name="sys_mon.xml"/>
</modules>
  • The main_freq parameter (in Hz) allows to specify the frequency of the main loop. Default is 60 Hz, for rotorcraft you should use 512 Hz.

Firmware and Hardware definitions

This is one example of a pretty standard quadcopter firmware definition:

File: conf/airframes/myplane.xml
  <firmware name="rotorcraft">
    <target name="sim" board="pc">
      <subsystem name="fdm"   type="nps"/>
    </target>

    <target name="ap" board="booz_1.0"/>

    <configure name="MODEM_BAUD" value="B57600"/><!--this is already the default, add and change this line only if needed-->

    <define name="USE_ADAPT_HOVER"/>
    <define name="GUIDANCE_H_USE_REF"/>

    <subsystem name="radio_control" type="ppm"/>
    <subsystem name="telemetry"     type="transparent"/>
    <subsystem name="actuators"     type="mkk"/>
    <subsystem name="imu"           type="b2_v1.1"/>
    <subsystem name="gps"           type="ublox"/>
    <subsystem name="ahrs"          type="cmpl"/>
    <subsystem name="ins"           type="hff"/>
  </firmware>

Select your Board

The airframe file must include the description of the controller board and it's low-level settings. This is done in the firmware section by specifying the board attribute for the target "ap" (autopilot).

Select the appropriate board: "twog_1.0", "tiny_2.11", "tiny_2.1", "tiny_1.1", "tiny_0.99", "booz_1.0", "lisa_l_1.0", "lisa_l_1.1", "pc"


File: conf/airframes/myplane.xml
  <firmware name="rotorcraft">
    <target name="sim" 			board="pc"/>
    <target name="ap" 			board="booz_1.0"/>
     ...
  </firmware>

Radio Control

The Paparazzi autopilot can interface directly with the PWM signal from any standard hobby R/C receiver. Signal decoding configuration settings for this are stored in the Radio Control file.

Just specify the appropriate subsystem in your firmware section:

File: conf/airframes/myplane.xml
  <firmware name="rotorcraft">
    <target name="sim" 			board="pc"/>
    <target name="ap" 			board="booz_1.0"/>
     ...
    <subsystem name="radio_control"     type="ppm"/>
  </firmware>

On the autopilots with a STM32 processor (lisa) you can use the type spektrum.

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 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.

Paparazzi 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 in your firmware section. You can currently choose between the types transparent and xbee_api.

File: conf/airframes/myplane.xml
  <firmware name="rotorcraft">
    <target name="ap" 			board="booz_1.0"/>
     ...
    <subsystem name="telemetry"     type="transparent"/>
  </firmware>

The correct UART is already defined by default according to your board. The default modem baudrate is 57600baud.

If you use different baud rate or UART set the according parameters, e.g.

File: conf/airframes/myplane.xml
  <firmware name="rotorcraft">
    <target name="ap" 			board="booz_1.0"/>
     ...
    <subsystem name="telemetry"     type="transparent">
      <configure name="MODEM_BAUD"          value="B9600"/>
      <configure name="MODEM_PORT"          value="UART1"/>
    </subsystem>
  </firmware>

GPS

For rotorcraft you can use the GPS types: 'ublox' and 'skytraq'. The ublox type is good for both lea-4p and lea-5h.

File: conf/airframes/myplane.xml
  <firmware name="rotorcraft">
    <target name="ap" 			board="booz_1.0"/>
     ...
    <subsystem name="gps"               type="ublox"/>
  </firmware>

The serial port settings must match that of the GPS:

The correct UART is already defined by default according to your board. The default gps baudrate is 38400baud.

If you use different baud rates set the according parameters, e.g.

File: conf/airframes/myplane.xml
  <firmware name="rotorcraft">
    <target name="ap" 			board="booz_1.0"/>
     ...
    <subsystem name="gps"               type="ublox">
      <configure name="GPS_BAUD"          value="B9600"/>
    </subsystem>
  </firmware>

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 thrugh the UART Tunnel and Configured with u-center

IMU

Add the imu subsystem with the type you are using. Currently possible IMU subsystems are "b2_v1.0", "b2_v1.1", "b2_v1.2", "crista" and "aspirin". Other IMUs can be used through modules or you can just add a subsystem makefile for your own. Also see the IMU calibration page.

File: conf/airframes/myplane.xml
  <firmware name="rotorcraft">
    <target name="ap" 		board="booz_1.0"/>
     ...
    <subsystem name="imu"       type="b2_v1.0"/>
  </firmware>

Paparazzi has a parameterto define the orientation of the IMU with respect to the body of the vehicle:

File: conf/airframes/myplane.xml
    <define name="BODY_TO_IMU_PHI"   value="RadOfDeg( 0. )"/>
    <define name="BODY_TO_IMU_THETA" value="RadOfDeg( 0. )"/>
    <define name="BODY_TO_IMU_PSI"   value="RadOfDeg( 0. )"/>

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="rotorcraft">
    <target name="ap" board="booz_1.0"/>
     ...
    <subsystem name="ahrs" type="cmpl"/>
  </firmware>

For the latest integer complementary filter (ic):

File: conf/airframes/myplane.xml
  <firmware name="rotorcraft">
    <target name="ap" board="booz_1.0"/>
     ...
    <subsystem name="ahrs" type="ic"/>
  </firmware>

 <section name="AHRS" prefix="AHRS_">
    <define name="PROPAGATE_FREQUENCY" value="512"/>
    <define name="H_X" value=" 0.51562740288882"/>
    <define name="H_Y" value="-0.05707735220832"/>
    <define name="H_Z" value=" 0.85490967783446"/>
  </section>

H is the normalised local magnetic field which can be derived by following instructions on the IMU calibration page here.

Other flags of interest are;

  • AHRS_PROPAGATE_LOW_PASS_RATES : apply a low pass filter on rotational velocity
  • AHRS_MAG_UPDATE_YAW_ONLY : use mag to update yaw only

There is a test program ( sw/airborne/test/ahrs/compare_ahrs.py ) to compare different AHRS implementations on simple test cases.

INS

The optional INS (Integrated Navigation System) subsystem contains estimations filter to e.g. fuse GPS and IMU data for better position and speed estimates.

File: conf/airframes/myplane.xml
  <firmware name="rotorcraft">
    <target name="ap" board="booz_1.0"/>
     ...
    <subsystem name="ins" type="hff"/>
  </firmware>

You can also compensate for GPS lag in hff (horizontal filter float) if it is known (in seconds):

File: conf/airframes/myplane.xml
  <firmware name="rotorcraft">
    <target name="ap" board="booz_1.0"/>
     ...
    <subsystem name="ins" type="hff">
      <define name="GPS_LAG=0.2"/>
    </subsystem>
  </firmware>

Beware, this code is kinda bad/ugly and should be replaced/improved!