Difference between revisions of "Subsystem/imu"
m |
Earthpatrol (talk | contribs) |
||
(32 intermediate revisions by 6 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 hideprefix=always>Subsystems</categorytree> | |||
Currently possible '''I'''nertial'''M'''easurement'''U'''nit subsystems are | |||
__TOC__ | |||
{| class="wikitable" style="text-align:center" border="1" | |||
! type !! architectures !! firmwares !! defaults<sup>'''1'''</sup> !! notes | |||
|- | |||
|''analog'' || all || all || no || | |||
|- | |||
|''apogee'' || stm32f4 || all || yes || mounted on the [[Apogee/v1.00|Apogee autpilot board]] | |||
|- | |||
|''aspirin_v1.0'' || all || all || yes || [[AspirinIMU]] via SPI with DMA | |||
|- | |||
|''aspirin_v1.5'' || all || all || yes || [[AspirinIMU]] via SPI with DMA | |||
|- | |||
|''aspirin_v2.1'' || all || all || yes || [[AspirinIMU]] via SPI with DMA | |||
|- | |||
|''aspirin_v2.2'' || all || all || yes || [[AspirinIMU]] via SPI with DMA | |||
|- | |||
|''aspirin_i2c_v1.0'' || all || all || yes || [[AspirinIMU]] via I2C | |||
|- | |||
|''aspirin_i2c_v1.5'' || all || all || yes || [[AspirinIMU]] via I2C | |||
|- | |||
|''aspirin2_i2c'' || all || all || no || [[AspirinIMU]] v2 via I2C | |||
|- | |||
|''b2_v1.0'' || all || all || no || | |||
|- | |||
|''b2_v1.1'' || all || all || no || | |||
|- | |||
|''b2_v1.2'' || all || all || no || | |||
|- | |||
|''drotek_10dof_v2'' || all || all || yes || [[Sensors/imu#Drotek_MPU6050-hmc5883-ms5611|Drotek IMU board with MPU6050, HMC5883 (MS5611 not used in this driver)]] | |||
|- | |||
|''elle0'' || stm32f4 || all || yes || mounted on the [[Elle0|Elle0 autpilot board]] | |||
|- | |||
|''gl1'' || all || all || yes || I2C IMU with L3G4200, ADXL345, HMC5883 and BMP085 from GoodLuckBuy | |||
|- | |||
|''yai'' || all || all || yes || | |||
|- | |||
|''krooz_sd'' || stm32f4 || all || yes || mounted on the [[KroozSD]] autopilot board | |||
|- | |||
|''navgo'' || lpc21 || all || yes || mounted on the [[NavGo_v3|NavGo autpilot board]] | |||
|- | |||
|''umarim'' || lpc21 || all || yes || mounted on the [[Umarim_v10|Umarim autpilot board]] | |||
|- | |||
|''crista'' || || || no || | |||
|- | |||
|''crista_hmc5843'' || || || no || | |||
|- | |||
|''ppzuav'' || lpc21 || fw || no || | |||
|- | |||
|''vectornav'' || all || all || no || Vectornav INS module used as IMU only (measures rates and acceleration), connected over UART | |||
|} | |||
'''1.''' Has default ''GYRO_x'' and ''ACCEL_x'' values from datasheet. | |||
Add the ''imu'' subsystem with the appropriate ''type'' to your firmware section: | |||
{{Box Code|conf/airframes/myplane.xml| | {{Box Code|conf/airframes/myplane.xml| | ||
< | <source lang="xml"> | ||
<firmware name="fixedwing or rotorcraft"> | <firmware name="fixedwing or rotorcraft"> | ||
... | ... | ||
<subsystem name="imu" type=" | <subsystem name="imu" type="aspirin_v2.1"/> | ||
</firmware> | </firmware> | ||
</ | </source> | ||
}} | |||
Other IMUs can be used through modules or you can just add a subsystem makefile for your own. | |||
== Defining the calibration == | |||
In the IMU section the [[ImuCalibration|IMU calibration]] is defined.<br> | |||
'''Some IMUs (see table above) have defaults defined. You may leave out the ''GYRO_x'' and ''ACCEL_x'' defines to use the datasheet values.''' | |||
=== Magnetometer === | |||
The magnetometer always needs to be [[ImuCalibration#Calibrating_the_Magnetometer|calibrated]] (Unless you want to disable it).<br> | |||
Here is a resulting minimal example: | |||
{{Box Code|conf/airframes/myplane.xml| | |||
<source lang="xml"> | |||
<section name="IMU" prefix="IMU_"> | |||
<define name="MAG_X_SENS" value="3.17378921476" integer="16"/> | |||
<define name="MAG_Y_SENS" value="3.14663275967" integer="16"/> | |||
<define name="MAG_Z_SENS" value="3.26531022727" integer="16"/> | |||
<define name="MAG_X_NEUTRAL" value="2059"/> | |||
<define name="MAG_Y_NEUTRAL" value="1944"/> | |||
<define name="MAG_Z_NEUTRAL" value="2099"/> | |||
</section> | |||
</source> | |||
}} | |||
==== 45deg Mag hack ==== | |||
If your magnetometer axes are rotated by 45deg around z. (e.g. with external mag on booz imu v1.0) | |||
{{Box Code|conf/airframes/myplane.xml| | |||
<source lang="xml"> | |||
<section name="IMU" prefix="IMU_"> | |||
... | |||
<define name="MAG_45_HACK" value="1" /> | |||
<!--define name="MAG_X_SENS" value="5.14821844457 * sqrt(2)/2" integer="16"/--> | |||
<!--define name="MAG_Y_SENS" value="5.11810156597 * sqrt(2)/2" integer="16"/--> | |||
<define name="MAG_X_SENS" value="3.640340173" integer="16"/> | |||
<define name="MAG_Y_SENS" value="3.619044324" integer="16"/> | |||
<define name="MAG_Z_SENS" value="5.07618333556" integer="16"/> | |||
</section> | |||
</source> | |||
}} | }} | ||
=== | === Gyro and Accel === | ||
Defining these values will override any defaults that most IMUs already have (see table at top for which drivers provide defaults that work unless you want to change the cofiguration).<br/>See the [[ImuCalibration]] page for the actual calibration instructions. | |||
{{Box Code|conf/airframes/myplane.xml| | {{Box Code|conf/airframes/myplane.xml| | ||
< | <source lang="xml"> | ||
<section name="IMU" prefix="IMU_"> | <section name="IMU" prefix="IMU_"> | ||
<define name="GYRO_P_NEUTRAL" value="32362" /> | <define name="GYRO_P_NEUTRAL" value="32362" /> | ||
Line 40: | Line 124: | ||
<define name="ACCEL_Z_NEUTRAL" value="32941"/> | <define name="ACCEL_Z_NEUTRAL" value="32941"/> | ||
< | ... | ||
</section> | |||
</source> | |||
}} | |||
== Defining the orientation of the IMU == | |||
Paparazzi has parameters to define the orientation of the IMU with respect to the body of the vehicle. | |||
'''Important''' Not all algorithms properly deal with any BODY_TO_IMU orientation. See the notes for the respective implementation at [[Subsystem/ahrs]] and the [https://github.com/paparazzi/paparazzi/issues/93 issue on github]. | |||
For the algorithms not supporting that, the only way to properly deal with 90deg rotations is to just change the sensors channels (e.g. so that what are normally the x-axis gyros and accels become the y-axis sensors, etc.) | |||
[[Image:Quad-top.png|240px]] | |||
<define name=" | Not defining these values is the same as setting them to zero. | ||
<define name=" | {{Box Code|conf/airframes/myplane.xml| | ||
<define name=" | <source lang="xml"> | ||
<section name="IMU" prefix="IMU_"> | |||
... | |||
<define name="BODY_TO_IMU_PHI" value="0.0" unit="deg"/> | |||
<define name="BODY_TO_IMU_THETA" value="0.0" unit="deg"/> | |||
<define name="BODY_TO_IMU_PSI" value="0.0" unit="deg"/> | |||
</section> | </section> | ||
</ | </source> | ||
}} | }} | ||
'''Note: Angles are always defined in radians, but by setting ''unit="deg"'' you can [[Units|define them in degrees and they are automatically converted to rad]].''' | |||
* The positive 90 degree offset, parallel mount example: | |||
[[Image:Quad-top_IMU-90.png|240px]] | |||
Configured as: | |||
{{Box Code|conf/airframes/myplane.xml| | {{Box Code|conf/airframes/myplane.xml| | ||
< | <source lang="xml"> | ||
<section name="IMU" prefix="IMU_"> | <section name="IMU" prefix="IMU_"> | ||
... | ... | ||
<define name=" | <define name="BODY_TO_IMU_PHI" value="0.0" unit="deg"/> | ||
<define name="BODY_TO_IMU_THETA" value="0.0" unit="deg"/> | |||
<define name="BODY_TO_IMU_PSI" value="90.0" unit="deg"/> | |||
<define name=" | |||
<define name=" | |||
</section> | </section> | ||
</ | </source> | ||
}} | }} | ||
===In Flight Tuning=== | |||
* Switch to AHRS telemetry mode and look for the fields that are prefixed with imu_ | |||
[[Image:AHRS telemetry.png|240px]] | |||
90 degree positive offset example | |||
* Open a Real_time plotter from the paparazzi console tools tab and drag int32 body_phi and int32 body_theta into the plotter box. | |||
* Hover rotorcraft (preferably indoors) to record data. | |||
* Copy the (best fit) recorded values into the airframe BODY_TO_IMU defines: | |||
{{Box Code|conf/airframes/myplane.xml| | {{Box Code|conf/airframes/myplane.xml| | ||
< | <source lang="xml"> | ||
<section name="IMU" prefix="IMU_"> | <section name="IMU" prefix="IMU_"> | ||
... | ... | ||
<define name="BODY_TO_IMU_PHI" value=" | <define name="BODY_TO_IMU_PHI" value="1.5" unit="deg"/> | ||
<define name="BODY_TO_IMU_THETA" value=" | <define name="BODY_TO_IMU_THETA" value="-0.5" unit="deg"/> | ||
<define name="BODY_TO_IMU_PSI" value=" | <define name="BODY_TO_IMU_PSI" value="90." unit="deg"/> | ||
</section> | </section> | ||
</ | </source> | ||
}} | }} | ||
* Ignore 'on the ground' resting values as depicted in the above image. They will change once the vehicle is in flight. The aim is to get the 'in flight' values of "int32 body_phi" & "int32 body_theta" as close to zero as possible. | |||
[[Category:User_Documentation]] [[Category:Subsystems]] |
Latest revision as of 15:32, 11 July 2017
Currently possible InertialMeasurementUnit subsystems are
type | architectures | firmwares | defaults1 | notes |
---|---|---|---|---|
analog | all | all | no | |
apogee | stm32f4 | all | yes | mounted on the Apogee autpilot board |
aspirin_v1.0 | all | all | yes | AspirinIMU via SPI with DMA |
aspirin_v1.5 | all | all | yes | AspirinIMU via SPI with DMA |
aspirin_v2.1 | all | all | yes | AspirinIMU via SPI with DMA |
aspirin_v2.2 | all | all | yes | AspirinIMU via SPI with DMA |
aspirin_i2c_v1.0 | all | all | yes | AspirinIMU via I2C |
aspirin_i2c_v1.5 | all | all | yes | AspirinIMU via I2C |
aspirin2_i2c | all | all | no | AspirinIMU v2 via I2C |
b2_v1.0 | all | all | no | |
b2_v1.1 | all | all | no | |
b2_v1.2 | all | all | no | |
drotek_10dof_v2 | all | all | yes | Drotek IMU board with MPU6050, HMC5883 (MS5611 not used in this driver) |
elle0 | stm32f4 | all | yes | mounted on the Elle0 autpilot board |
gl1 | all | all | yes | I2C IMU with L3G4200, ADXL345, HMC5883 and BMP085 from GoodLuckBuy |
yai | all | all | yes | |
krooz_sd | stm32f4 | all | yes | mounted on the KroozSD autopilot board |
navgo | lpc21 | all | yes | mounted on the NavGo autpilot board |
umarim | lpc21 | all | yes | mounted on the Umarim autpilot board |
crista | no | |||
crista_hmc5843 | no | |||
ppzuav | lpc21 | fw | no | |
vectornav | all | all | no | Vectornav INS module used as IMU only (measures rates and acceleration), connected over UART |
1. Has default GYRO_x and ACCEL_x values from datasheet.
Add the imu subsystem with the appropriate type to your firmware section:
File: conf/airframes/myplane.xml |
<firmware name="fixedwing or rotorcraft">
...
<subsystem name="imu" type="aspirin_v2.1"/>
</firmware>
|
Other IMUs can be used through modules or you can just add a subsystem makefile for your own.
Defining the calibration
In the IMU section the IMU calibration is defined.
Some IMUs (see table above) have defaults defined. You may leave out the GYRO_x and ACCEL_x defines to use the datasheet values.
Magnetometer
The magnetometer always needs to be calibrated (Unless you want to disable it).
Here is a resulting minimal example:
File: conf/airframes/myplane.xml |
<section name="IMU" prefix="IMU_">
<define name="MAG_X_SENS" value="3.17378921476" integer="16"/>
<define name="MAG_Y_SENS" value="3.14663275967" integer="16"/>
<define name="MAG_Z_SENS" value="3.26531022727" integer="16"/>
<define name="MAG_X_NEUTRAL" value="2059"/>
<define name="MAG_Y_NEUTRAL" value="1944"/>
<define name="MAG_Z_NEUTRAL" value="2099"/>
</section>
|
45deg Mag hack
If your magnetometer axes are rotated by 45deg around z. (e.g. with external mag on booz imu v1.0)
File: conf/airframes/myplane.xml |
<section name="IMU" prefix="IMU_">
...
<define name="MAG_45_HACK" value="1" />
<!--define name="MAG_X_SENS" value="5.14821844457 * sqrt(2)/2" integer="16"/-->
<!--define name="MAG_Y_SENS" value="5.11810156597 * sqrt(2)/2" integer="16"/-->
<define name="MAG_X_SENS" value="3.640340173" integer="16"/>
<define name="MAG_Y_SENS" value="3.619044324" integer="16"/>
<define name="MAG_Z_SENS" value="5.07618333556" integer="16"/>
</section>
|
Gyro and Accel
Defining these values will override any defaults that most IMUs already have (see table at top for which drivers provide defaults that work unless you want to change the cofiguration).
See the ImuCalibration page for the actual calibration instructions.
File: conf/airframes/myplane.xml |
<section name="IMU" prefix="IMU_">
<define name="GYRO_P_NEUTRAL" value="32362" />
<define name="GYRO_Q_NEUTRAL" value="32080" />
<define name="GYRO_R_NEUTRAL" value="32096" />
<define name="GYRO_P_SENS" value="1.1032765" integer="16" />
<define name="GYRO_Q_SENS" value="1.1360802599" integer="16" />
<define name="GYRO_R_SENS" value="1.1249874614" integer="16" />
<define name="ACCEL_X_SENS" value="2.45932966" integer="16"/>
<define name="ACCEL_Y_SENS" value="2.45106376" integer="16"/>
<define name="ACCEL_Z_SENS" value="2.47825717" integer="16"/>
<define name="ACCEL_X_NEUTRAL" value="31886"/>
<define name="ACCEL_Y_NEUTRAL" value="32162"/>
<define name="ACCEL_Z_NEUTRAL" value="32941"/>
...
</section>
|
Defining the orientation of the IMU
Paparazzi has parameters to define the orientation of the IMU with respect to the body of the vehicle.
Important Not all algorithms properly deal with any BODY_TO_IMU orientation. See the notes for the respective implementation at Subsystem/ahrs and the issue on github. For the algorithms not supporting that, the only way to properly deal with 90deg rotations is to just change the sensors channels (e.g. so that what are normally the x-axis gyros and accels become the y-axis sensors, etc.)
Not defining these values is the same as setting them to zero.
File: conf/airframes/myplane.xml |
<section name="IMU" prefix="IMU_">
...
<define name="BODY_TO_IMU_PHI" value="0.0" unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="0.0" unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="0.0" unit="deg"/>
</section>
|
Note: Angles are always defined in radians, but by setting unit="deg" you can define them in degrees and they are automatically converted to rad.
- The positive 90 degree offset, parallel mount example:
Configured as:
File: conf/airframes/myplane.xml |
<section name="IMU" prefix="IMU_">
...
<define name="BODY_TO_IMU_PHI" value="0.0" unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="0.0" unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="90.0" unit="deg"/>
</section>
|
In Flight Tuning
- Switch to AHRS telemetry mode and look for the fields that are prefixed with imu_
90 degree positive offset example
- Open a Real_time plotter from the paparazzi console tools tab and drag int32 body_phi and int32 body_theta into the plotter box.
- Hover rotorcraft (preferably indoors) to record data.
- Copy the (best fit) recorded values into the airframe BODY_TO_IMU defines:
File: conf/airframes/myplane.xml |
<section name="IMU" prefix="IMU_">
...
<define name="BODY_TO_IMU_PHI" value="1.5" unit="deg"/>
<define name="BODY_TO_IMU_THETA" value="-0.5" unit="deg"/>
<define name="BODY_TO_IMU_PSI" value="90." unit="deg"/>
</section>
|
- Ignore 'on the ground' resting values as depicted in the above image. They will change once the vehicle is in flight. The aim is to get the 'in flight' values of "int32 body_phi" & "int32 body_theta" as close to zero as possible.