accel/gyro changes in master - accel calibration required

331 views
Skip to first unread message

Randy Mackay

unread,
Mar 11, 2015, 10:52:17 PM3/11/15
to drones-...@googlegroups.com, Jonathan Challinger, Andrew Tridgell

 

     A bunch of patches from Jon and Tridge have just gone into master.  My understanding is the changes include:

·         Accelerometer range increased from 8G to 16G.

o   We believe that the reason copters always climb (in AltHold, Loiter, etc) when they have really high vibration is because of accelerometer value “clipping”.

o   Everyone will need to re-do their accelerometer calibration.  Copter and Plane users should hit an arming check requiring this.  Because the offsets and scaling are stored in new areas in eeprom if you later downgrade you’ll find that your old accel calibration values have returned.  As per usual, just be careful not to load accel scaling and offsets from a param file produced by an older version of the firmware.

·         Replace MPU6k hardware filtering with software filtering.

o   MPU6K_FILTER is replaced by GYRO_FILTER and ACCEL_FILTER which allow changing the accel and gyros filtering separately.  Note that “0” means no filtering which won’t fly well but will allow seeing pure raw IMU values in the dataflash logs (previously only post-filtered values were visible).

·         Support coning correction (requires some changes to EKF that are not in master yet).  I’ll leave Jon or Paul to explain this.

·         Sensor rotation is done before applying offsets.

o   Previously if you ever changed the AHRS_ORIENT parameter you would need to re-do your accel calibration.  This is no longer required.

·         Additional checking during accel calibration

o   This reduces the chance of a bad accel calibration happening by checking the users has placed the board in all 6 directions.

o   Also check for accelerometer failures during the calibration

·         Removed 1D calibration for Plane, Rover.

   

-Randy

OlliW

unread,
Mar 12, 2015, 5:19:38 AM3/12/15
to drones-...@googlegroups.com, mr.cha...@gmail.com, tri...@tridgell.net
 Sensor rotation is done before applying offsets.

o   Previously if you ever changed the AHRS_ORIENT parameter you would need to re-do your accel calibration.  This is no longer required.


my answer is based solely on the info deducable from this two lines of text (have not analyzed code)

this still can't be the best approach
it assumes, and therefore requires, that AHRS_ORIENT was correct in the calibration
one should first apply the calibration results and then rotate sensor data, AND in the calibration one should use the raw sensor data before any rotation
that way the calibration is always correct irrespective of what is done to the sensor data in the code later on
that's at least how I do it, for the same reasons of avoiding recalibrations as much as possible, even in case of user mistakes  ;)



·         Removed 1D calibration for Plane, Rover.

that's sad, I would have hoped that a simple tare would come also to copter ... unless it's used for acrobatics a 1D is really not too bad for a copter ... I've fooled around also with AQ, and it has such a thing, and it's nice. My reasons would be
* it especially makes getting into air quick and fairly reliable. I find the ArduCopters 6 point Calibration a bit daunting at first, it's fairly likely not to get too good results, i.e. one needs some "training" to go through it and some "experience" to evaluate if it has been good and if not what one needs to do better. A simple tare is kind of fool proof.
* a tare can be always done quickly on the field, so one can use the copter without to much issue in the cold morning and the hot midday ...
as said, I think that for many use cases the copter is not tilted/rolled much, and if, then not for long, so that a 1D tare is quite fine
(at least with the MPU6k, for which I only can speak, since it's acc magnitudes are very close to the supposed to be magnitudes)

just my 2 cents :)

Jesus Alvarez

unread,
Mar 12, 2015, 10:18:26 AM3/12/15
to drones-...@googlegroups.com
Sad too to see the useful 1D calib disappearing.

I thought it was going the opposite direction as I remember a discussion were 1D calib was going to be added to copter?

6 pos calib is a real pain on an already built copter or plane (and some times it is not possible to remove the Pixhawk/APM). And some times (due to the difficulty) ends being a worse calibration than the counterpart 1D.

David Pawlak

unread,
Mar 12, 2015, 10:26:40 AM3/12/15
to drones-...@googlegroups.com
At least it can be done without the camara and heavy batteries. :p

Paul Riseborough

unread,
Mar 12, 2015, 10:02:19 PM3/12/15
to drones-...@googlegroups.com
The airframe does not have to to be placed at exact angles for the roll/pitch/upside down orientations for the fit algorithm to work - angles of 10 degrees  from vertical  work OK and having a stable position where the airframe doesn't move during the sample is more important. The only orientation that has to be accurate is the level orientation at the start. The simple single point level is less able to handle situations where the board is misaligned with the copter or the IMU(s) have bad intrinsic scale factors. However I can appreciate on large airframes it could be a pain. 
 
-Paul

Holger Steinhaus

unread,
Mar 13, 2015, 3:26:12 AM3/13/15
to drones-...@googlegroups.com
+1 again for a simple tare function. Its absolutely a pain to do full accell calibrations - and the best part of it is to press a key in the GCS while holding holding the copter with both hands. I am also pretty sure that it introduces lots of additional errors, compared to a clean 6p calibration with the Pixhawk only on the desk.

The usual reason for "trim" deviatons in copter is simply some minor tension introduced by cables, together with the super-soft foam mounting of the Pixhawk. I doubt that doing a 6 point calibration brings any benefit here. I do not see why either the scale or the alignment with frame should change significantly in the scenario.

BTW, the various in-flight trimming options are not a valid replacement for leveling, as the online shop for ordering calm weather doesn't deliver very reliably in certain peak seasons...

Holger

OlliW

unread,
Mar 13, 2015, 5:32:29 AM3/13/15
to drones-...@googlegroups.com
"The airframe does not have to to be placed at exact angles for the roll/pitch/upside down orientations for the fit algorithm to work ...  The simple single point level is less able to handle situations where the board is misaligned with the copter"

no, the 6-point procedure is then necessarily relative to the sensor frame, and thus missalignments of the sensor frame with respect to the copter frame are neither detected nor corrected for
(assuming reasonable ranges of missalignment)

"The simple single point level is less able to handle situations where ... the IMU(s) have bad intrinsic scale factor"

true, but as said before that's not the case for the MPU6k! Its intrinsic scale factors are quite good, here offsets are the culprit.

Randy Mackay

unread,
Mar 13, 2015, 8:30:01 AM3/13/15
to drones-...@googlegroups.com

 

     We can definitely add in a preflight calibration that does a “level” which will not be a full accel calibration but instead set the AHRS_TRIM_X and Y values depending upon the board’s current lean.  This level feature is built into the 6-position (aka 3D) accel calibration but it’s not hard to make it work as a stand-alone feature.

 

     In case there’s any question, the 3D accel calibration really is important though for the accel based position estimates (aka inertial nav).  If the accels offsets and scaling aren’t accurate the position estimates go bad very quickly.  If you want to try it out for yourself, it’s possible by first loading plane on your pixhawk or APM and doing the “1D” accel calibration.  Record the INS_ACC* parameter values, then load copter (which will wipe out your params) and then overwrite the params with the values from the 1D calibration.  Arm, fly and reply back with how it goes!

 

-Randy

--
You received this message because you are subscribed to the Google Groups "drones-discuss" group.
To unsubscribe from this group and stop receiving emails from it, send an email to drones-discus...@googlegroups.com.
For more options, visit https://groups.google.com/d/optout.

Randy Mackay

unread,
Mar 13, 2015, 8:34:37 AM3/13/15
to drones-...@googlegroups.com

 

     By the way, this request is already on the to-do list:

       https://github.com/diydrones/ardupilot/issues/1856

 

-Randy

 

From: Randy Mackay [mailto:rmac...@yahoo.com]
Sent: 13-Mar-15 9:30 PM
To: 'drones-...@googlegroups.com'
Subject: RE: [Bulk] [drones-discuss] Re: accel/gyro changes in master - accel calibration required

 

 

     We can definitely add in a preflight calibration that does a “level” which will not be a full accel calibration but instead set the AHRS_TRIM_X and Y values depending upon the board’s current lean.  This level feature is built into the 6-position (aka 3D) accel calibration but it’s not hard to make it work as a stand-alone feature.

 

     In case there’s any question, the 3D accel calibration really is important though for the accel based position estimates (aka inertial nav).  If the accels offsets and scaling aren’t accurate the position estimates go bad very quickly.  If you want to try it out for yourself, it’s possible by first loading plane on your pixhawk or APM and doing the “1D” accel calibration.  Record the INS_ACC* parameter values, then load copter (which will wipe out your params) and then overwrite the params with the values from the 1D calibration.  Arm, fly and reply back with how it goes!

 

-Randy

 

From: drones-...@googlegroups.com [mailto:drones-...@googlegroups.com] On Behalf Of OlliW
Sent: 13-Mar-15 6:32 PM
To: drones-...@googlegroups.com
Subject: [Bulk] [drones-discuss] Re: accel/gyro changes in master - accel calibration required

 

"The airframe does not have to to be placed at exact angles for the roll/pitch/upside down orientations for the fit algorithm to work ...  The simple single point level is less able to handle situations where the board is misaligned with the copter"

--

Paul Riseborough

unread,
Mar 14, 2015, 1:13:02 AM3/14/15
to drones-...@googlegroups.com
Holger - accel offsets can change by 0.5 m/s/s due to temperature changes going from summer to winter, so until we add temperature compensation or control, the 6 point calibration is necessary for  many users and anyone with a large copter should devise a jig of some description to hold it at the different orientations. As previously  stated, all orientations other than the first one in the 'level' position do not have to be at 90 degrees as the algorithm used is solving a simultaneous equation for 3 scale factors and 3 offsets.

-Paul

Holger Steinhaus

unread,
Mar 14, 2015, 5:24:55 AM3/14/15
to drones-...@googlegroups.com
Hi Paul,
 
Holger - accel offsets can change by 0.5 m/s/s due to temperature changes going from summer to winter, so until we add temperature compensation or control, the 6 point calibration is necessary for  many users
Is it that bad? I wonder what is happening on a usual winter day, where I start to fly at -5°C and reach about 50°C at the end of the flight. I am pretty sure that I have seen this range in the past - may be I should dig for a log.

 
and anyone with a large copter should devise a jig of some description to hold it at the different orientations. 
Yes, I think I should consider that approach.

Holger

Robert Lefebvre

unread,
Mar 14, 2015, 8:22:07 AM3/14/15
to drones-discuss
Holger, I have one example that is, IIRC, 1.5 m/s/s difference between -10C and 20C.

--

Paul Riseborough

unread,
Mar 16, 2015, 2:28:41 AM3/16/15
to drones-...@googlegroups.com
We really do need to get either temperature control or temperature offset calibration sorted if these boards are going to suitable for out of the box commercial use. A resistance heater over the MPU6000 regulated using the reported internal temperature would be easy to do and would keep it in a smaller temperature range. Alternatively a lookup table or to store IMU offsets (or curve-fit parameters) vs temperature would be fairly easy to add in code. The laborious part is doing the testing to populate the tables, but I reckon a serious commercial user would be prepared to pay extra for a board that was calibrated and verified. 

john...@gmail.com

unread,
Mar 16, 2015, 6:25:52 AM3/16/15
to drones-...@googlegroups.com
> but I reckon a serious commercial user would be prepared to pay extra for a board that was calibrated and verified.

That is how most of the more expensive industrial IMU boards are manufactured. There is hardly any technical difference from what we are doing, but a combination of pricier sensors and automated heat/movement calibration on every board during manufacturing makes them deliver better and consistent results.

Robert Lefebvre

unread,
Mar 16, 2015, 10:39:15 AM3/16/15
to drones-discuss
I've seen indication from at least one hobby helicopter FBL manufacturer, that they are doing gyro scale-factor calibration of their system across temperatures.  Every unit is calibrated.  At least that's what they claim.  Do you think that's likely?  It seems slightly implausible to me, even at the high price-point they have?

On 16 March 2015 at 06:25, <john...@gmail.com> wrote:
> but I reckon a serious commercial user would be prepared to pay extra for a board that was calibrated and verified.

That is how most of the more expensive industrial IMU boards are manufactured. There is hardly any technical difference from what we are doing, but a combination of pricier sensors and automated heat/movement calibration on every board during manufacturing makes them deliver better and consistent results.

--

Paul Riseborough

unread,
Mar 16, 2015, 2:07:19 PM3/16/15
to drones-...@googlegroups.com
Calibration of offsets only can be done relatively cheaply with a cal function in the software, and a means of powering the board and activating the cal mode while it is in a thermal chamber. One thermal chamber could easily cal 100+ boards at a time. Calibration of scale factors is another matter entirely - moving tables in thermal chambers ....

Robert Lefebvre

unread,
Mar 16, 2015, 2:42:27 PM3/16/15
to drones-discuss
Yes, exactly.  Scale factor seems much harder, but he seemed to indicate that he was doing that.

john...@gmail.com

unread,
Mar 16, 2015, 7:01:41 PM3/16/15
to drones-...@googlegroups.com
None of this is very complicated, but specialized and potentially expensive.

- First of your need a temperature controlled chamber, ideally big enough so that you can also perform other sensor tests inside it.
- Gyro is perhaps the easiest one. A motorized turntable with accurate speed and angle control in combination with a jig to hold the IMU at different angles, should take care of that.
- Accelerometers are a bit trickier, since you will need some kind of motorized rail system for controlled acceleration and deceleration.

Combining them to get the most realistic calibration will definitively be the biggest challenge. The pro's usually end up with some expensive robotic arm to solve this.

Robert Lefebvre

unread,
Mar 16, 2015, 7:43:11 PM3/16/15
to drones-discuss
Yeah, I guess a 3-axis gimbal on a single axis turn-table is a simple solution.  I wonder if you could do acceleration, simply by displacing the IMU from the center of rotation of the turntable?

I wonder how many FBL units are typically sold?  There's a big difference between processing 10-100 units a day, vs 1000+ per day.  10-100 you could do on a simple home-made system.  1000+, you need something industrial for sure.

Andrew Tridgell

unread,
Mar 16, 2015, 10:47:22 PM3/16/15
to Paul Riseborough, drones-...@googlegroups.com
Hi Paul,

> We really do need to get either temperature control or temperature offset
> calibration sorted if these boards are going to suitable for out of the box
> commercial use.

As a first step towards this I've just added a Temp field to the IMU,
IMU2 and IMU3 dataflash log messages. This gives us the temperatures
reported by the IMUs. They are similar to (but not the same as) the baro
temperature.

If we do want to do temperature calibration tables then it needs to be
based on the temperature of each sensor, not on the baro temperature, so
I thought this would be worthwhile.

To get the lsm303d temperature it also needs an update to the lsm303d
driver in PX4Firmware, which I have also pushed to master.

Cheers, Tridge
Reply all
Reply to author
Forward
0 new messages