在实际DIY-Mark4的Ardupilot5寸机的试飞过程经常出现“error compass variance”的警告。
无论怎么校准磁力计: 1) 反复校准; 2) 空旷环境(排除周围干扰); 3) 引线屏蔽干扰;都无法获得期望效果。
【1】Why “error compass variance” when flip?
【2】Copter 4.4.0 “Error Compass Variance” during a big turn in mission, any idea?
Ardupilot 4.4.0 beta3 Mark4 + Mission Planner + 433 Telemetry 城北公园试飞
Ardupilot 4.4.0 Mark4 + Mission + Error Compass Variance
关于磁力计的校准,主要是按照Ardupilot - Compass Calibration上的步骤进行。
其次,考虑了以下内容:
最终的结果:
实际:在大幅度,短时间大幅方向改变,系统会报告“error compass variance”。
综上所述,磁力计的校准没有达到比较好的数值。
那么对于当前的布线,磁力计的位置暂时都无法再做进一步的调整情况下,怎么办???
Ardupilot提供一个高阶的磁力计校准工具magfit_WMM,该工具可以依赖飞行日志数据进行磁力计校准(主要采用GPS + 磁力计)。
$ magfit_WMM.py --help
usage: magfit_WMM.py [-h] [--condition CONDITION] [--mag MAG] [--reduce REDUCE] [--min-scale MIN_SCALE] [--max-scale MAX_SCALE] [--max-offset MAX_OFFSET]
[--min-diag MIN_DIAG] [--max-diag MAX_DIAG] [--min-offdiag MIN_OFFDIAG] [--max-offdiag MAX_OFFDIAG] [--max-cmot MAX_CMOT] [--no-offset-change]
[--no-cmot-change] [--elliptical] [--cmot] [--cmot-throttle] [--lat LAT] [--lon LON] [--att-source ATT_SOURCE] [--save-plot] [--save-params]
[--iter ITER]
LOG
fit best estimate of magnetometer offsets, diagonals, off-diagonals, cmot and scaling using WMM target
positional arguments:
LOG
options:
-h, --help show this help message and exit
--condition CONDITION
select packets by condition
--mag MAG mag index, 1 for first mag
--reduce REDUCE reduce data points by given factor
--min-scale MIN_SCALE
min scale factor
--max-scale MAX_SCALE
max scale factor
--max-offset MAX_OFFSET
max offset
--min-diag MIN_DIAG min diagonal
--max-diag MAX_DIAG max diagonal
--min-offdiag MIN_OFFDIAG
min off diagonal
--max-offdiag MAX_OFFDIAG
max off diagonal
--max-cmot MAX_CMOT max compassmot
--no-offset-change don't change offsets
--no-cmot-change don't change cmot
--elliptical fit elliptical corrections
--cmot fit compassmot corrections using current
--cmot-throttle fit compassmot corrections using throttle
--lat LAT latitude
--lon LON longitude
--att-source ATT_SOURCE
attitude source message
--save-plot save plot to .png file
--save-params save params to .param file
--iter ITER max optimization iterations
鉴于ArduPilot飞控之DIY-F450计划采用的ESC不具备电流计功能,因此,下面分析的数据无法将电流大小考虑进去。
--cmot
$ magfit_WMM.py --elliptical --cmot .bin
--cmot-throttle
$ magfit_WMM.py --elliptical --cmot-throttle .bin
$ magfit_WMM.py --elliptical .bin
$ magfit_WMM.py --elliptical --cmot-throttle 2023-08-22_08-54-01.bin
Processing log 2023-08-22_08-54-01.bin
Attitude source XKF1
Earth field: Vector3(336.95, -35.44, 352.00) strength 489 declination -6.0 degrees
Extracted 4747 points
Current: Vector3(-222.53, 121.33, -384.86) diag: Vector3(0.95, 0.97, 1.10) offdiag: Vector3(0.00, 0.00, -0.01) cmot_mode: 0.0 cmot: Vector3(0.00, 0.00, 0.00) scale: 1.00
offsets: [-222.15219688 121.23396301 -384.4187851 ] scale: 1.5
offsets: [-221.72106618 121.11495453 -384.12112245] scale: 0.9247570736414995
offsets: [-218.79445361 120.23965997 -381.51263087] scale: 0.778029922359718
offsets: [-220.87580604 120.73813023 -383.26642928] scale: 1.025073674344154
offsets: [-220.95809642 120.04232051 -382.83360789] scale: 1.174473102561532
offsets: [-220.13040924 120.00371359 -382.35778728] scale: 1.0189337806909413
offsets: [-220.0733846 120.04655968 -382.482919 ] scale: 0.9827237325054003
offsets: [-214.07032664 115.97587795 -376.7767648 ] scale: 0.9849088661367147
offsets: [-194.71187853 102.83541881 -358.38585724] scale: 0.9776549639589784
offsets: [-173.11368164 88.47437706 -337.9725422 ] scale: 1.0779557665531978
offsets: [-145.48548693 69.29526905 -311.93471981] scale: 0.8583461393043492
offsets: [-154.512547 75.53084029 -320.428447 ] scale: 0.9587034539129123
offsets: [-126.75568091 56.91148791 -294.39999829] scale: 1.1747666503888117
offsets: [-121.33361891 53.14660603 -289.42974779] scale: 0.9564612245989689
offsets: [-102.28878946 40.55281817 -271.73318371] scale: 1.10972902842562
offsets: [ -89.76128963 32.4423429 -260.11867925] scale: 1.1132966395227941
offsets: [ -41.12792698 0.63242098 -214.88484302] scale: 0.7096478847749303
offsets: [ -73.47785147 21.79762479 -245.05780217] scale: 1.0858134061583995
offsets: [ -65.52907628 16.83120531 -237.96244156] scale: 1.1058091841603634
offsets: [ -52.09527928 7.97173244 -225.19526705] scale: 1.0753824878591225
offsets: [ -37.9176106 -0.624849 -212.36830556] scale: 1.109417573462849
offsets: [ -31.40010072 -4.71265754 -206.32508959] scale: 1.0991628661879471
offsets: [ -23.11695213 -9.84167841 -198.64677151] scale: 1.0899566886077856
offsets: [ -4.95671046 -20.87505431 -181.82852655] scale: 1.0677300896701807
offsets: [ -8.76700816 -18.26559019 -185.40092646] scale: 1.0741103905316043
offsets: [ -8.52549963 -17.96184586 -185.21341832] scale: 1.074025698589448
offsets: [ -8.50821483 -14.55051574 -185.42158101] scale: 1.0737833239745809
offsets: [ -10.14782999 -5.13512689 -187.42677824] scale: 1.0722580570692737
offsets: [ -18.11815965 18.80072665 -195.78437735] scale: 1.0653302464960472
offsets: [ -19.49994328 20.05357197 -196.99792467] scale: 1.061887958164364
offsets: [ -25.81353808 26.52032025 -202.62655411] scale: 1.0558189675276024
offsets: [ -20.09914507 23.02995558 -197.37368245] scale: 1.0528280273477462
offsets: [ -19.76799314 23.53454823 -197.07656082] scale: 1.0537793464003244
offsets: [ -18.67708995 28.02250027 -196.09385812] scale: 1.0558909239225045
offsets: [ -20.36784139 36.98368833 -197.66128864] scale: 1.0547297007001597
offsets: [ -23.95991731 55.78812436 -201.01898374] scale: 1.0477447386120509
offsets: [ -24.12930229 65.18736145 -201.35315181] scale: 1.0434939320512697
offsets: [ -43.24607846 128.3357228 -220.02631237] scale: 1.0241317329043658
offsets: [ -5.23125407 113.28714809 -184.93018776] scale: 0.9837808110676521
offsets: [ -24.1532395 119.76022981 -202.38357832] scale: 1.0053345555609827
offsets: [ -27.1118157 120.35933997 -205.07014364] scale: 1.0077295609839156
offsets: [ -26.46784639 124.62583664 -204.50939059] scale: 1.004572345609096
offsets: [ -26.9456794 124.40755105 -204.90717418] scale: 1.0061221359403898
offsets: [ -26.80393404 124.50263098 -204.75561841] scale: 1.0054819462957536
offsets: [ -26.71192182 124.4294301 -204.61364141] scale: 1.0051257091862336
offsets: [ -26.69234563 124.47197499 -204.55520899] scale: 1.0051332910369202
offsets: [ -26.69555096 124.68582395 -204.46334868] scale: 1.005445073049674
offsets: [ -26.7495827 124.98279261 -204.42100664] scale: 1.0058872941034958
offsets: [ -26.81744366 125.18584833 -204.36689961] scale: 1.0060661347383006
offsets: [ -26.93309551 125.52927695 -204.14157034] scale: 1.0059798410396597
offsets: [ -27.14054994 126.05923691 -203.42835332] scale: 1.0049838150882069
offsets: [ -27.47952068 126.92097879 -201.27320995] scale: 1.0011020573667297
offsets: [ -28.02581785 128.35922603 -195.09406302] scale: 0.9888631065462361
offsets: [ -29.02462826 131.13106861 -175.43189226] scale: 0.9486693306726774
offsets: [ -28.88793551 128.89304349 -172.70895057] scale: 0.9436269315593786
offsets: [ -28.19220164 125.74216406 -172.06503755] scale: 0.9416695220939588
offsets: [ -27.9059954 125.02867421 -172.25492707] scale: 0.9415997769493977
offsets: [ -27.84968993 125.16274803 -172.38865896] scale: 0.9418606728575778
offsets: [ -27.87249252 125.32955584 -172.40387293] scale: 0.9419355097191013
offsets: [ -27.89471903 125.43592298 -172.37035509] scale: 0.9419143982060183
offsets: [ -27.89925552 125.44033345 -172.3503954 ] scale: 0.9418931702789292
offsets: [ -27.89925552 125.44033345 -172.3503954 ] scale: 0.9418931702789292
Optimization terminated successfully (Exit mode 0)
Current function value: 38.262622255577526
Iterations: 62
Function evaluations: 885
Gradient evaluations: 62
New: Vector3(-27.90, 125.44, -172.35) diag: Vector3(1.20, 1.14, 0.80) offdiag: Vector3(0.00, -0.20, -0.03) cmot_mode: 1 cmot: Vector3(10.00, 10.00, -10.00) scale: 0.94
COMPASS_OFS_X -27
COMPASS_OFS_Y 125
COMPASS_OFS_Z -172
COMPASS_DIA_X 1.200
COMPASS_DIA_Y 1.143
COMPASS_DIA_Z 0.800
COMPASS_ODI_X 0.001
COMPASS_ODI_Y -0.200
COMPASS_ODI_Z -0.030
COMPASS_MOT_X 10.000
COMPASS_MOT_Y 10.000
COMPASS_MOT_Z -10.000
COMPASS_SCALE 0.94
COMPASS_MOTCT 1
$ magfit_WMM.py --elliptical --cmot-throttle 2023-08-22_09-07-27.bin
Processing log 2023-08-22_09-07-27.bin
Attitude source XKF1
Earth field: Vector3(336.95, -35.44, 352.00) strength 489 declination -6.0 degrees
Extracted 4065 points
Current: Vector3(-222.53, 121.33, -384.86) diag: Vector3(0.95, 0.97, 1.10) offdiag: Vector3(0.00, 0.00, -0.01) cmot_mode: 0.0 cmot: Vector3(0.00, 0.00, 0.00) scale: 1.00
offsets: [-222.15119743 121.25483513 -384.46229935] scale: 1.5
offsets: [-221.74488693 121.15861003 -384.128454 ] scale: 0.9347362017016234
/usr/lib/python3/dist-packages/scipy/optimize/_optimize.py:284: RuntimeWarning: Values in x were outside bounds during a minimize step, clipping to bounds
warnings.warn("Values in x were outside bounds during a "
offsets: [-217.27583458 120.08064002 -379.99687839] scale: 0.6
offsets: [-220.69401916 120.7811526 -383.07467543] scale: 0.9869417045669464
offsets: [-220.56184301 120.21875584 -382.61517511] scale: 1.0072937190277629
offsets: [-220.76469165 120.65325086 -383.04868231] scale: 0.9402266671481865
offsets: [-218.18921671 119.06635393 -380.05174088] scale: 0.9398653553210581
offsets: [-205.65711733 111.35575045 -365.50237953] scale: 0.9384793022885184
offsets: [-171.56232993 90.67330702 -326.15207183] scale: 1.0264896436469382
offsets: [-137.74560397 69.44120979 -286.95637087] scale: 0.939731984202873
offsets: [-130.01413063 64.68563343 -278.14185821] scale: 0.9087459099135348
offsets: [-122.48909859 59.90162945 -269.60928725] scale: 1.0514179393965184
offsets: [ -97.67998227 44.73715694 -241.26455693] scale: 1.0364318224279203
offsets: [ -63.36787976 23.41056943 -201.79273065] scale: 0.8370478236651971
offsets: [ -28.0250353 2.08129296 -161.53011494] scale: 1.0009733772962366
offsets: [ -21.46691907 -2.07289145 -153.80262404] scale: 0.9045181307096279
offsets: [ -17.14605812 -4.57718436 -149.02625466] scale: 0.942406650111862
offsets: [ -3.4644283 -12.93684168 -133.28080138] scale: 0.8869970300200424
offsets: [ 30.10174353 -33.11629582 -94.89641428] scale: 0.9380665431696007
offsets: [ 21.61850192 -27.94275942 -104.64546814] scale: 0.9382179508441861
offsets: [ 27.18237208 -31.31760084 -98.20048921] scale: 0.9235070736699629
offsets: [ 26.04581273 -30.3798815 -99.63471847] scale: 0.9267455624900247
offsets: [ 23.52250041 -29.01264643 -102.43454621] scale: 0.9320210323657098
offsets: [ 24.26576868 -29.43446577 -101.55943728] scale: 0.9317532103316899
offsets: [ 24.23141719 -29.35322794 -101.55128446] scale: 0.9317505606722764
offsets: [ 24.38883366 -28.86781932 -100.92828864] scale: 0.9305595319100947
offsets: [ 23.53713815 -25.48724365 -99.72851887] scale: 0.9266767107532046
offsets: [ 22.84161768 -19.77776545 -96.53990401] scale: 0.9173429065143219
offsets: [ 22.05549172 -15.65049615 -94.83898405] scale: 0.9138448863876591
offsets: [ 14.51614171 2.64356837 -93.78807819] scale: 0.8990301704015244
offsets: [ 7.71820494 12.77780489 -97.47786461] scale: 0.8958531382608036
offsets: [ 5.00134128 14.23493425 -100.82229166] scale: 0.8969815135834155
offsets: [ 3.07053345 15.61035724 -103.00266736] scale: 0.8979311941355261
offsets: [ 2.40913407 16.15215564 -103.79966544] scale: 0.8982384606847524
offsets: [ 2.22929524 16.38597077 -104.07563835] scale: 0.8980682572372812
offsets: [ 2.1418039 16.81322996 -104.2661583 ] scale: 0.8974529019072872
offsets: [ 2.73866616 16.5540796 -103.65276916] scale: 0.8971299342212293
offsets: [ 3.54086118 16.34886327 -102.95878387] scale: 0.8968947068936374
offsets: [ 4.31026013 16.44253112 -102.61836647] scale: 0.8971665638922296
offsets: [ 4.69910514 16.48471536 -103.09153497] scale: 0.8983480078095325
offsets: [ 5.77419779 16.06415264 -105.91532798] scale: 0.9038327898209638
offsets: [ 6.24549133 16.07062991 -107.96751003] scale: 0.9067796592567305
offsets: [ 6.6497211 16.34681296 -110.00729092] scale: 0.9088012581203047
offsets: [ 6.6028475 16.87331325 -110.78678435] scale: 0.9087061400303893
offsets: [ 6.32427166 17.78015579 -111.33141643] scale: 0.908060313412323
offsets: [ 5.57244929 20.26222025 -112.71958538] scale: 0.9070560707602762
offsets: [ 3.53367109 27.20645734 -116.90526936] scale: 0.9059718404716061
offsets: [ 4.0287047 32.18847425 -122.25885108] scale: 0.9101276875487846
offsets: [ 4.09883969 43.88222442 -135.20777722] scale: 0.9222271411862665
offsets: [ 3.83932924 45.63413881 -136.54625568] scale: 0.92518045751734
offsets: [ 3.45668837 48.16616587 -138.01658541] scale: 0.9286566069549825
offsets: [ 2.46825765 52.06983967 -141.38014163] scale: 0.9319525169102478
offsets: [ -2.38836914 71.27559781 -158.30750566] scale: 0.9454644639315144
offsets: [ -4.20170726 76.08529234 -160.97948682] scale: 0.9454104264499754
offsets: [ -4.19703017 73.7488123 -157.47555264] scale: 0.9393044765083985
offsets: [ -4.63061142 72.73903477 -152.95558379] scale: 0.9272254097643498
offsets: [ -5.02197444 76.03975065 -154.57417488] scale: 0.9269465795315135
offsets: [ -7.95291419 94.03707914 -162.04484586] scale: 0.9266869836286596
offsets: [ -7.93278916 101.25998508 -160.22328877] scale: 0.923920375839638
offsets: [ -9.51155158 105.95551553 -160.44747214] scale: 0.9255142124160121
offsets: [ -8.40839717 103.15509449 -155.22910375] scale: 0.9280652468227363
offsets: [ -9.74548641 109.41609715 -158.91161248] scale: 0.929861530510485
offsets: [ -9.4881143 111.00698547 -159.27793435] scale: 0.9308784493299466
offsets: [ -9.76318514 108.28585526 -158.56020769] scale: 0.9287482897670142
offsets: [ -9.49924989 106.91969415 -158.11170754] scale: 0.9283634350998382
offsets: [ -9.52589898 106.56164519 -157.94464851] scale: 0.9282022207533429
offsets: [ -9.5290643 106.59538373 -157.93094048] scale: 0.9281802463364024
offsets: [ -9.5290643 106.59538373 -157.93094048] scale: 0.9281802463364024
Optimization terminated successfully (Exit mode 0)
Current function value: 43.3875537695191
Iterations: 68
Function evaluations: 964
Gradient evaluations: 68
New: Vector3(-9.53, 106.60, -157.93) diag: Vector3(1.20, 1.12, 0.80) offdiag: Vector3(0.01, -0.20, 0.00) cmot_mode: 1 cmot: Vector3(10.00, 10.00, -10.00) scale: 0.93
COMPASS_OFS_X -9
COMPASS_OFS_Y 106
COMPASS_OFS_Z -157
COMPASS_DIA_X 1.200
COMPASS_DIA_Y 1.117
COMPASS_DIA_Z 0.800
COMPASS_ODI_X 0.011
COMPASS_ODI_Y -0.200
COMPASS_ODI_Z 0.003
COMPASS_MOT_X 10.000
COMPASS_MOT_Y 10.000
COMPASS_MOT_Z -10.000
COMPASS_SCALE 0.93
COMPASS_MOTCT 1
$ magfit_WMM.py --elliptical 2023-08-22_08-54-01.bin
Processing log 2023-08-22_08-54-01.bin
Attitude source XKF1
Earth field: Vector3(336.95, -35.44, 352.00) strength 489 declination -6.0 degrees
Extracted 4747 points
Current: Vector3(-222.53, 121.33, -384.86) diag: Vector3(0.95, 0.97, 1.10) offdiag: Vector3(0.00, 0.00, -0.01) cmot_mode: 0.0 cmot: Vector3(0.00, 0.00, 0.00) scale: 1.00
offsets: [-222.15219688 121.23396301 -384.4187851 ] scale: 1.5
offsets: [-221.72594997 121.11625921 -384.12689775] scale: 0.9247734826802956
offsets: [-218.82544229 120.24794538 -381.54886941] scale: 0.7783091079158704
offsets: [-220.89043179 120.74207405 -383.28319372] scale: 1.0252204220295724
offsets: [-220.98785055 120.05214743 -382.86626615] scale: 1.1743640555447779
offsets: [-220.24821509 120.08431815 -382.50042585] scale: 1.0133741966420666
offsets: [-219.91864286 119.93107532 -382.34241161] scale: 0.9833172539520423
offsets: [-214.31195982 116.10140005 -377.0313087 ] scale: 0.9842142719869312
offsets: [-192.90277247 101.45666849 -356.75704991] scale: 0.9754104923526181
offsets: [-112.01874939 46.67011318 -280.32164129] scale: 0.9021968810857341
offsets: [-110.69714405 45.47259723 -278.98793246] scale: 0.8175447790652505
offsets: [ -83.48571971 26.9265424 -253.34469138] scale: 0.8813915407624164
offsets: [ -92.47390647 33.26309028 -261.82366296] scale: 1.0937763886935818
/usr/lib/python3/dist-packages/scipy/optimize/_optimize.py:284: RuntimeWarning: Values in x were outside bounds during a minimize step, clipping to bounds
warnings.warn("Values in x were outside bounds during a "
offsets: [-123.8392906 54.79988381 -291.19208996] scale: 0.985711864251096
offsets: [ -53.35298875 6.85766926 -224.79713261] scale: 1.0721467746755027
offsets: [ -57.92243463 10.16097465 -229.15396763] scale: 1.102591437030134
offsets: [ -48.2144825 3.88955305 -219.99299223] scale: 1.1202268504315396
offsets: [ -35.14803806 -4.71538938 -207.67618925] scale: 1.1052486815721791
offsets: [ -24.62090273 -11.68217703 -197.71603023] scale: 1.0857929788017968
offsets: [ -18.56512899 -15.51466502 -192.00957296] scale: 1.0884321858543085
offsets: [ -11.61942915 -19.90489691 -185.45401064] scale: 1.0799876995297986
offsets: [ -6.61335169 -22.99706927 -180.72669897] scale: 1.0710924941073108
offsets: [ -7.06280632 -22.45143822 -181.14952484] scale: 1.0702065559852048
offsets: [ -7.31943333 -21.2930115 -181.38817711] scale: 1.067984912940587
offsets: [ -8.29255538 -18.48205206 -182.29762515] scale: 1.0638357009944164
offsets: [ -11.14389592 -9.80059296 -184.96075357] scale: 1.0544826468890023
offsets: [ -19.49684716 16.75755123 -192.76051888] scale: 1.0316621349714092
offsets: [ -29.56489091 77.45431316 -202.05996702] scale: 0.9754225654839247
offsets: [ -16.30920599 99.42308714 -189.4922807 ] scale: 0.9454403351071247
offsets: [ -23.82587111 153.56202718 -196.70911892] scale: 0.996055088242762
offsets: [ -27.73953807 104.5356656 -200.42996532] scale: 1.0214333484868836
offsets: [ -41.1714807 144.27793374 -212.99161889] scale: 1.0001860150437993
offsets: [ -27.82910826 123.19324088 -200.42094469] scale: 0.9913427904136569
offsets: [ -25.43462181 126.07287909 -198.1500846 ] scale: 0.9911249982572675
offsets: [ -25.13252215 126.04452085 -197.84979909] scale: 0.989010505426515
offsets: [ -25.54887923 126.38008085 -198.22417415] scale: 0.9890094842415683
offsets: [ -25.73339006 126.62604049 -198.36113455] scale: 0.9889040441998316
offsets: [ -25.70311944 126.58494379 -198.30771549] scale: 0.9887312825506993
offsets: [ -25.64509094 126.4413218 -198.18034596] scale: 0.9883327648706992
offsets: [ -25.59397016 126.25356255 -197.99454004] scale: 0.9877373928234437
offsets: [ -25.53877316 125.9220311 -197.6037511 ] scale: 0.9865372654439043
offsets: [ -25.51121261 125.60199655 -196.95683396] scale: 0.984818418514157
offsets: [ -25.50187902 124.83209853 -194.82287062] scale: 0.9793491249283808
offsets: [ -25.57258471 124.08481677 -191.21495699] scale: 0.9708511648368455
offsets: [ -25.84971234 123.24806763 -182.81378034] scale: 0.9524767939982965
offsets: [ -26.36050352 123.3738248 -176.69614601] scale: 0.9415135915330011
offsets: [ -27.18618852 125.55855909 -173.67095636] scale: 0.9420142509227734
offsets: [ -26.7610734 126.44949912 -173.78461747] scale: 0.9415228087047672
offsets: [ -26.66394418 126.8089128 -174.1986238 ] scale: 0.9420780281482376
offsets: [ -26.65461637 126.82673107 -174.28332704] scale: 0.9422315451024793
offsets: [ -26.64754914 126.8082533 -174.28055262] scale: 0.9422286979511184
offsets: [ -26.64754914 126.8082533 -174.28055262] scale: 0.9422286979511184
Optimization terminated successfully (Exit mode 0)
Current function value: 38.51226949812001
Iterations: 52
Function evaluations: 587
Gradient evaluations: 52
New: Vector3(-26.65, 126.81, -174.28) diag: Vector3(1.20, 1.14, 0.80) offdiag: Vector3(0.00, -0.20, -0.03) cmot_mode: 0 cmot: Vector3(0.00, 0.00, 0.00) scale: 0.94
COMPASS_OFS_X -26
COMPASS_OFS_Y 126
COMPASS_OFS_Z -174
COMPASS_DIA_X 1.200
COMPASS_DIA_Y 1.142
COMPASS_DIA_Z 0.800
COMPASS_ODI_X 0.002
COMPASS_ODI_Y -0.200
COMPASS_ODI_Z -0.030
COMPASS_MOT_X 0.000
COMPASS_MOT_Y 0.000
COMPASS_MOT_Z 0.000
COMPASS_SCALE 0.94
COMPASS_MOTCT 0
$ magfit_WMM.py --elliptical 2023-08-22_09-07-27.bin
Processing log 2023-08-22_09-07-27.bin
Attitude source XKF1
Earth field: Vector3(336.95, -35.44, 352.00) strength 489 declination -6.0 degrees
Extracted 4065 points
Current: Vector3(-222.53, 121.33, -384.86) diag: Vector3(0.95, 0.97, 1.10) offdiag: Vector3(0.00, 0.00, -0.01) cmot_mode: 0.0 cmot: Vector3(0.00, 0.00, 0.00) scale: 1.00
offsets: [-222.15119743 121.25483513 -384.46229935] scale: 1.5
offsets: [-221.74982084 121.15965466 -384.13367793] scale: 0.934749955283912
offsets: [-217.31778472 120.08951567 -380.04149506] scale: 0.6000000001448269
offsets: [-220.71061082 120.78479666 -383.09203932] scale: 0.9870496981954998
offsets: [-220.59711642 120.23336906 -382.65451578] scale: 1.0066238565954069
offsets: [-220.79005105 120.66231646 -383.07624753] scale: 0.9401142445665388
offsets: [-218.26475298 119.09314882 -380.13325252] scale: 0.9397756035544652
offsets: [-205.96780151 111.46320838 -365.83494482] scale: 0.9382962760115365
offsets: [ -66.79855444 25.67939123 -204.44848119] scale: 0.8469317693675614
offsets: [ 19.15442101 -27.58665168 -104.61939395] scale: 0.8737011518429816
offsets: [-128.1264411 63.54682257 -275.27604317] scale: 0.9725931411776225
offsets: [ -20.18450914 -3.23678647 -150.20846909] scale: 0.9841246386237443
offsets: [ -20.46189476 -3.11591049 -150.64975918] scale: 1.032318313040759
offsets: [ 6.53025162 -19.49908805 -119.25590307] scale: 0.9218280088202537
offsets: [ 27.43410202 -32.13442126 -95.29078805] scale: 0.9576113310146238
offsets: [ -23.09477623 -0.3361458 -153.76589208] scale: 0.9380280170109025
offsets: [ 31.83239606 -34.75642527 -90.03843946] scale: 0.9269729495326042
offsets: [ 30.66736316 -34.07633694 -91.33550089] scale: 0.9234448523933241
offsets: [ 24.50037735 -30.27102166 -98.47973825] scale: 0.9308784265229136
offsets: [ 25.14552769 -30.63826001 -97.71034376] scale: 0.9284707354169212
offsets: [ 25.17894398 -30.62872858 -97.65221835] scale: 0.9287209949075428
offsets: [ 25.18069294 -30.535872 -97.58411863] scale: 0.9288477197152155
offsets: [ 24.92843511 -29.72892651 -97.40819723] scale: 0.9289074167993275
offsets: [ 24.55675737 -27.80655166 -96.61854652] scale: 0.9273270886991353
offsets: [ 23.21470808 -22.06906091 -94.6268833 ] scale: 0.9212012680030897
offsets: [ 19.8956128 -11.4318124 -92.26992801] scale: 0.9102724680965131
offsets: [ 1.40168127e+01 -6.70106772e-02 -9.35173720e+01] scale: 0.901479040531787
offsets: [ 9.09354326 7.41462417 -96.09225441] scale: 0.8962111482360827
offsets: [ 5.75447356 11.00038167 -99.00066209] scale: 0.8939417898281853
offsets: [ 5.56871056 10.62721711 -99.6677926 ] scale: 0.8945953606383511
offsets: [ 5.74270668 10.14684652 -99.83328194] scale: 0.8949539145693808
offsets: [ 6.422011 9.03068715 -99.86975168] scale: 0.8956199284709689
offsets: [ 7.04635224 8.34034516 -99.76493683] scale: 0.8958724257878209
offsets: [ 8.24791626 7.64410842 -99.75123216] scale: 0.8961938646906921
offsets: [ 9.40583581 8.26764272 -100.63147807] scale: 0.8966125963913574
offsets: [ 10.12681508 13.57827665 -104.95042215] scale: 0.8981291066881023
offsets: [ 8.41448798 30.00196079 -117.56204994] scale: 0.9027119374454601
offsets: [ 1.65981729 63.17651712 -142.32093487] scale: 0.9123130854387408
offsets: [ 0.42593581 70.70220828 -147.10041157] scale: 0.9172635613145815
offsets: [ -18.47892361 133.19181292 -177.13137002] scale: 0.936144525859846
offsets: [ -8.3886788 99.16788724 -154.92944356] scale: 0.9260453490740869
offsets: [ -13.13330084 125.10765594 -170.35174918] scale: 0.9316223698305381
offsets: [ -7.27384267 111.19831047 -161.87829517] scale: 0.9307414753494763
offsets: [ -8.19054855 108.05330215 -160.16386603] scale: 0.9285859441240681
offsets: [ -8.53281906 108.41365331 -159.8430863 ] scale: 0.9280121459216091
offsets: [ -8.48808029 108.61469945 -159.8370083 ] scale: 0.9281478448340703
offsets: [ -8.46992651 108.86849288 -159.83224032] scale: 0.9282416104925225
offsets: [ -8.47180238 108.85622362 -159.82523472] scale: 0.9282407701922394
Optimization terminated successfully (Exit mode 0)
Current function value: 43.497384214132474
Iterations: 48
Function evaluations: 545
Gradient evaluations: 48
New: Vector3(-8.47, 108.86, -159.83) diag: Vector3(1.20, 1.12, 0.80) offdiag: Vector3(0.01, -0.20, 0.00) cmot_mode: 0 cmot: Vector3(0.00, 0.00, 0.00) scale: 0.93
COMPASS_OFS_X -8
COMPASS_OFS_Y 108
COMPASS_OFS_Z -159
COMPASS_DIA_X 1.200
COMPASS_DIA_Y 1.118
COMPASS_DIA_Z 0.800
COMPASS_ODI_X 0.012
COMPASS_ODI_Y -0.200
COMPASS_ODI_Z 0.001
COMPASS_MOT_X 0.000
COMPASS_MOT_Y 0.000
COMPASS_MOT_Z 0.000
COMPASS_SCALE 0.93
COMPASS_MOTCT 0
选取其中一组2023-08-22_09-07-27(取另一组也是可以的):
New: Vector3(-8.47, 108.86, -159.83) diag: Vector3(1.20, 1.12, 0.80) offdiag: Vector3(0.01, -0.20, 0.00) cmot_mode: 0 cmot: Vector3(0.00, 0.00, 0.00) scale: 0.93
COMPASS_OFS_X -8
COMPASS_OFS_Y 108
COMPASS_OFS_Z -159
COMPASS_DIA_X 1.200
COMPASS_DIA_Y 1.118
COMPASS_DIA_Z 0.800
COMPASS_ODI_X 0.012
COMPASS_ODI_Y -0.200
COMPASS_ODI_Z 0.001
COMPASS_MOT_X 0.000
COMPASS_MOT_Y 0.000
COMPASS_MOT_Z 0.000
COMPASS_SCALE 0.93
COMPASS_MOTCT 0
New: Vector3(-9.53, 106.60, -157.93) diag: Vector3(1.20, 1.12, 0.80) offdiag: Vector3(0.01, -0.20, 0.00) cmot_mode: 1 cmot: Vector3(10.00, 10.00, -10.00) scale: 0.93
COMPASS_OFS_X -9
COMPASS_OFS_Y 106
COMPASS_OFS_Z -157
COMPASS_DIA_X 1.200
COMPASS_DIA_Y 1.117
COMPASS_DIA_Z 0.800
COMPASS_ODI_X 0.011
COMPASS_ODI_Y -0.200
COMPASS_ODI_Z 0.003
COMPASS_MOT_X 10.000
COMPASS_MOT_Y 10.000
COMPASS_MOT_Z -10.000
COMPASS_SCALE 0.93
COMPASS_MOTCT 1
油门与电流有一定的非线性关系,因此,使用该组磁力校准数据替换如下:
Parameters | After | Before |
---|---|---|
COMPASS_OFS_X | -9 | -222.529 |
COMPASS_OFS_Y | 106 | 121.3342 |
COMPASS_OFS_Z | -157 | -384.8638 |
COMPASS_DIA_X | 1.200 | 0.949006 |
COMPASS_DIA_Y | 1.117 | 0.9697881 |
COMPASS_DIA_Z | 0.800 | 1.100859 |
COMPASS_ODI_X | 0.011 | 0.004150782 |
COMPASS_ODI_Y | -0.200 | 0.004519831 |
COMPASS_ODI_Z | 0.003 | -0.01019889 |
COMPASS_MOT_X | 10.000 | 0 |
COMPASS_MOT_Y | 10.000 | 0 |
COMPASS_MOT_Z | -10.000 | 0 |
COMPASS_SCALE | 0.93 | 0 |
COMPASS_MOTCT | 1 | 0 |
在手动操作下翻滚时,还是会有相应的警告信息,但是巡航任务下,不会再出现“error compass variance”。
Ardupilot 4.4.0 Mark4 + Mission + Error Compass Variance + Fix
【1】Refining Calibration Parameters using a Flight Log
【2】Ardupilot - Compass Calibration
【3】四轴飞控DIY Mark4 - 优化后续二
【4】ArduPilot飞控之DIY-F450计划