ArduIMU

From PaparazziUAV
Jump to navigation Jump to search
The printable version is no longer supported and may have rendering errors. Please update your browser bookmarks and please use the default browser print function instead.
ArduIMU with i2c wires and serial connector
Tiny13 w/IMU
TWOG w/IMU

This page describes how to integrate an ArduIMU+ V2 (flat) into an existing Airframe/Paparazzi-Code.

  1. The ArduIMU communicates over i2c with the Paparazzi-AP. The wiring is pretty easy to do. Connect SDA, SCL, ground at the i2c pins. Supply the IMU with 5V at one of the three 5V pins. The 3.3V i2c pin stays unconnected. Do not connect 3.3V from the Paparazzi-AP to the ArduIMU as it internally generates it's own stable 3.3v supply.
  2. Integration into the Paparazzi software is realized as a module. This is an easy way to connect and test the software.
  3. This description shows how to use the ArduIMU without a separate GPS-Receiver and without a Compass/Magnetometer. The GPS-Data is sent by the Paparazzi-AP over i2c to the ArduIMU.
  4. There is an other airframe/main-AP we wrote which uses a magnetometer for yaw-drift compensation. We haven't written an installation guide for this configuration yet. But we will try to do this as soon as possible.

The Code has been integrated into the Paparazzi build system.



Airframe Adjustments

First, remove the infrared configuration and substitute the IMU configuration (which uses I2C) as follows :

In your airframe file (found usually in conf/airframes with a name like "MyAirframe.xml")

  • (1) Insert the software module :
<modules>
  <load name="ins_arduimu.xml"/>
</modules>
  • (2) Increase i2c queue length to 16, and reduce i2c clock speed:
<target name="ap"    board="...">
          ...
  <define name="I2C_TRANSACTION_QUEUE_LEN" value="16"/> 
  <define name="I2C0_SCLL" value="400"/> 
  <define name="I2C0_SCLH" value="400"/> 
</target>

If you don't already have it, you will also need to add this to your ap target too:

 <define name="USE_I2C0"/>
  • (3) Insert INS neutrals:
<section name="INS" prefix="INS_">
  <define name="ROLL_NEUTRAL_DEFAULT" value="0" unit="deg"/>
  <define name="PITCH_NEUTRAL_DEFAULT" value="0" unit="deg"/>
</section>
  • (4) Remove the infrared estimation :
remove the line that looks like the following:
<subsystem name="ahrs"         type="infrared"/>
or if you still have the older subsystem
<subsystem name="attitude"         type="infrared"/>

You may have to comment out the following two lines in the file ../paparazzi/sw/airborne/modules/ins/ins_arduimu.c for the code to compile:

 // float throttle_slew;
 // throttle_slew = V_CTL_THROTTLE_SLEW;

Also, if you want to be able to run SITL simulations on this airframe, you will need to add an ahrs subsystem to your simulation target:

 <target name="sim" board="pc">
   <subsystem name="ahrs" type="float_dcm"/>
   ...
 </target>

TODO: link to sample working airframe in git

NOTE: Martin Mueller has committed some ArduIMU changes to https://github.com/martinmm/paparazzi for review.

It is based on ArduIMU v1.7 and fixes the main issue which was printing serial data while in I2C interrupt, also includes Steve Joyce's fixes.

Additional features are running at 60Hz, having the possibility to use the Paparazzi ROLL_RATE loop and transferring the gps data as it is received rather than at a constant, non synchronized rate. The v1.7 uses gps 3D speed for centrifugal correction whereas the v1.8.2 uses 2D speed.

Bill Premerlani's paper is a little vague on that but it is thought that 3D should be more precise when climbing/descending. Maybe 2D is used as simple gps receivers don't have 3D speed?

An example airframe file is at /conf/airframes/mm/fixed-wing/fw_ins_arduimu.xml It controlled a Funjet in 55m circles climbing 6m/s nicely.

Aircraft Settings

  • (5) Use this Settings file: settings/tuning_basic_ins.xml

Magnetometer (Ignore for now)

TODO: post Magnetometer integration guide

Flash the ArduIMU

(6) Programming the ArduIMU for use with the Tiny includes using :

  1. Adapted software in sw/airborne/firmwares/non_ap/arduimu_Firmware_WithGps.
  2. Standard USB FTDI cable plugged into the header that comes with the arduimu (Match the wire colors with those written on the arduimu silkscreen GRN=Green BLK=Black)

Steps:

  • Plug in USB FTDI Cable to PC and ArduIMU (this also provides power)
  • Install the Arduino IDE using the Ubuntu Software Center or the following command line:
 $ sudo apt-get install arduino
  • Launch the Arduino IDE using the Dash (in Ubuntu 11.04) or the following command line:
 $ arduino
Arduino open sketch.png

(TODO: Using the graphical interface is probably not necessary as the flashing seems to use avrdude command line utility)

  • Open project/sketch (File->open , point to paparazzi/sw/airborne/firmwares/non_ap/arduimu_Firmware_WithGps/arduimu/arduime.pde)
  • Clicking the "verify" button compiles
  • Clicking the "upload" button flashes
    • You may need to select your com port in menu Tools->Serial Port
    • You may need to select Atmega328 in menu Tool->Board

For more information concerning flashing of the ArduIMU, read: http://code.google.com/p/ardu-imu/wiki/Code

Do we still need this or is everything in git now?

You can find the original ZHAW code here.

Install and test the ArduIMU

  • The current firmware does not implement a full rotation matrix calculation and instead assumes that the arduimu's "x" axis is aligned with the fuselage. When installing the device in your aircraft be sure to respect this constraint.
  • Clean and build your aircraft target in paparazzi center and flash your Tiny as usual
  • With your GCS session running, you should see attitudes messages including the new messages "xxx" and " xxx"

Hardware Considerations

So far, this setup has been successfully flown in the Maja and EasyStar aircraft. For faster more agile aircraft such as the Merlin or Funjet, the polling rate needs to be changed from 15 Hz to 50 Hz in the /conf/modules/ins_arduimu.xml file.

  <periodic fun="ArduIMU_periodic()" freq="50" autorun="TRUE"/> 
  <periodic fun="ArduIMU_periodicGPS()" freq="4" autorun="TRUE"/> 

The ArduIMU is sensitive to vibrations. Mount it on a thick piece of foam to dampen the vibrations.


Have Fun !

Analysis and Results

TODO: Compare IR and arduimu estimations for various flight conditions TODO: Fuse the two estimates together for robustness?

Please Post Results Here... Issues?