12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340134113421343134413451346134713481349135013511352135313541355135613571358135913601361136213631364136513661367136813691370137113721373137413751376137713781379138013811382138313841385138613871388138913901391139213931394139513961397139813991400140114021403140414051406140714081409141014111412141314141415141614171418141914201421142214231424142514261427142814291430143114321433143414351436143714381439144014411442144314441445144614471448144914501451145214531454145514561457145814591460146114621463146414651466146714681469147014711472147314741475147614771478147914801481148214831484148514861487148814891490149114921493149414951496149714981499150015011502150315041505150615071508150915101511151215131514151515161517151815191520152115221523152415251526152715281529153015311532153315341535153615371538153915401541154215431544154515461547154815491550155115521553155415551556155715581559156015611562156315641565156615671568156915701571157215731574157515761577157815791580158115821583158415851586158715881589159015911592159315941595159615971598159916001601160216031604160516061607160816091610161116121613161416151616161716181619162016211622162316241625162616271628162916301631163216331634163516361637163816391640164116421643164416451646164716481649165016511652165316541655165616571658165916601661166216631664166516661667166816691670167116721673167416751676167716781679168016811682168316841685168616871688168916901691169216931694169516961697169816991700170117021703170417051706170717081709171017111712171317141715171617171718171917201721172217231724172517261727172817291730173117321733173417351736173717381739174017411742174317441745174617471748174917501751175217531754175517561757175817591760176117621763176417651766176717681769177017711772177317741775177617771778177917801781178217831784178517861787178817891790179117921793179417951796179717981799180018011802180318041805180618071808180918101811181218131814181518161817181818191820182118221823182418251826182718281829183018311832183318341835183618371838183918401841184218431844184518461847184818491850185118521853185418551856185718581859186018611862186318641865186618671868186918701871187218731874187518761877187818791880188118821883188418851886188718881889189018911892189318941895189618971898189919001901190219031904190519061907190819091910191119121913191419151916191719181919192019211922192319241925192619271928192919301931193219331934193519361937193819391940194119421943194419451946194719481949195019511952195319541955195619571958195919601961196219631964196519661967196819691970197119721973197419751976197719781979198019811982198319841985198619871988198919901991199219931994199519961997199819992000200120022003200420052006200720082009201020112012201320142015201620172018201920202021202220232024202520262027202820292030203120322033203420352036203720382039204020412042204320442045204620472048204920502051205220532054205520562057205820592060206120622063206420652066206720682069207020712072207320742075207620772078 |
- #include <assert.h>
- #include <AP_Common/AP_Common.h>
- #include <AP_HAL/AP_HAL.h>
- #include <AP_HAL/I2CDevice.h>
- #include <AP_HAL/SPIDevice.h>
- #include <AP_Math/AP_Math.h>
- #include <AP_Notify/AP_Notify.h>
- #include <AP_Vehicle/AP_Vehicle.h>
- #include <AP_BoardConfig/AP_BoardConfig.h>
- #include <AP_AHRS/AP_AHRS.h>
- #include "AP_InertialSensor.h"
- #include "AP_InertialSensor_BMI160.h"
- #include "AP_InertialSensor_Backend.h"
- #include "AP_InertialSensor_HIL.h"
- #include "AP_InertialSensor_L3G4200D.h"
- #include "AP_InertialSensor_LSM9DS0.h"
- #include "AP_InertialSensor_LSM9DS1.h"
- #include "AP_InertialSensor_Invensense.h"
- #include "AP_InertialSensor_SITL.h"
- #include "AP_InertialSensor_RST.h"
- #include "AP_InertialSensor_BMI055.h"
- #include "AP_InertialSensor_BMI088.h"
- #include "AP_InertialSensor_Invensensev2.h"
- #ifdef INS_TIMING_DEBUG
- #include <stdio.h>
- #define timing_printf(fmt, args...) do { printf("[timing] " fmt, ##args); } while(0)
- #else
- #define timing_printf(fmt, args...)
- #endif
- #ifndef HAL_DEFAULT_INS_FAST_SAMPLE
- #define HAL_DEFAULT_INS_FAST_SAMPLE 0
- #endif
- extern const AP_HAL::HAL& hal;
- #if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
- #define DEFAULT_GYRO_FILTER 20
- #define DEFAULT_ACCEL_FILTER 20
- #define DEFAULT_STILL_THRESH 2.5f
- #elif APM_BUILD_TYPE(APM_BUILD_APMrover2)
- #define DEFAULT_GYRO_FILTER 4
- #define DEFAULT_ACCEL_FILTER 10
- #define DEFAULT_STILL_THRESH 0.1f
- #else
- #define DEFAULT_GYRO_FILTER 20
- #define DEFAULT_ACCEL_FILTER 20
- #define DEFAULT_STILL_THRESH 0.1f
- #endif
- #define SAMPLE_UNIT 1
- #define GYRO_INIT_MAX_DIFF_DPS 0.1f
- const AP_Param::GroupInfo AP_InertialSensor::var_info[] = {
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("GYROFFS", 3, AP_InertialSensor, _gyro_offset[0], 0),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("GYR2OFFS", 7, AP_InertialSensor, _gyro_offset[1], 0),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("GYR3OFFS", 10, AP_InertialSensor, _gyro_offset[2], 0),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("ACCSCAL", 12, AP_InertialSensor, _accel_scale[0], 0),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("ACCOFFS", 13, AP_InertialSensor, _accel_offset[0], 0),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("ACC2SCAL", 14, AP_InertialSensor, _accel_scale[1], 0),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("ACC2OFFS", 15, AP_InertialSensor, _accel_offset[1], 0),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("ACC3SCAL", 16, AP_InertialSensor, _accel_scale[2], 0),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("ACC3OFFS", 17, AP_InertialSensor, _accel_offset[2], 0),
-
-
-
-
-
-
- AP_GROUPINFO("GYRO_FILTER", 18, AP_InertialSensor, _gyro_filter_cutoff, DEFAULT_GYRO_FILTER),
-
-
-
-
-
-
- AP_GROUPINFO("ACCEL_FILTER", 19, AP_InertialSensor, _accel_filter_cutoff, DEFAULT_ACCEL_FILTER),
-
-
-
-
-
- AP_GROUPINFO("USE", 20, AP_InertialSensor, _use[0], 1),
-
-
-
-
-
- AP_GROUPINFO("USE2", 21, AP_InertialSensor, _use[1], 1),
-
-
-
-
-
- AP_GROUPINFO("USE3", 22, AP_InertialSensor, _use[2], 1),
-
-
-
-
-
- AP_GROUPINFO("STILL_THRESH", 23, AP_InertialSensor, _still_threshold, DEFAULT_STILL_THRESH),
-
-
-
-
-
- AP_GROUPINFO("GYR_CAL", 24, AP_InertialSensor, _gyro_cal_timing, 1),
-
-
-
-
-
- AP_GROUPINFO("TRIM_OPTION", 25, AP_InertialSensor, _trim_option, 1),
-
-
-
-
-
- AP_GROUPINFO("ACC_BODYFIX", 26, AP_InertialSensor, _acc_body_aligned, 2),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("POS1", 27, AP_InertialSensor, _accel_pos[0], 0.0f),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("POS2", 28, AP_InertialSensor, _accel_pos[1], 0.0f),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_GROUPINFO("POS3", 29, AP_InertialSensor, _accel_pos[2], 0.0f),
-
-
-
-
-
- AP_GROUPINFO("GYR_ID", 30, AP_InertialSensor, _gyro_id[0], 0),
-
-
-
-
-
- AP_GROUPINFO("GYR2_ID", 31, AP_InertialSensor, _gyro_id[1], 0),
-
-
-
-
-
- AP_GROUPINFO("GYR3_ID", 32, AP_InertialSensor, _gyro_id[2], 0),
-
-
-
-
-
- AP_GROUPINFO("ACC_ID", 33, AP_InertialSensor, _accel_id[0], 0),
-
-
-
-
-
- AP_GROUPINFO("ACC2_ID", 34, AP_InertialSensor, _accel_id[1], 0),
-
-
-
-
-
- AP_GROUPINFO("ACC3_ID", 35, AP_InertialSensor, _accel_id[2], 0),
-
-
-
-
-
-
- AP_GROUPINFO("FAST_SAMPLE", 36, AP_InertialSensor, _fast_sampling_mask, HAL_DEFAULT_INS_FAST_SAMPLE),
-
-
- AP_SUBGROUPINFO(_notch_filter, "NOTCH_", 37, AP_InertialSensor, NotchFilterParams),
-
-
- AP_SUBGROUPINFO(batchsampler, "LOG_", 39, AP_InertialSensor, AP_InertialSensor::BatchSampler),
-
-
-
-
-
-
- AP_GROUPINFO("ENABLE_MASK", 40, AP_InertialSensor, _enable_mask, 0x7F),
-
-
- AP_SUBGROUPINFO(_harmonic_notch_filter, "HNTCH_", 41, AP_InertialSensor, HarmonicNotchFilterParams),
-
- AP_GROUPEND
- };
- AP_InertialSensor *AP_InertialSensor::_singleton = nullptr;
- AP_InertialSensor::AP_InertialSensor() :
- _board_orientation(ROTATION_NONE),
- _log_raw_bit(-1)
- {
- if (_singleton) {
- AP_HAL::panic("Too many inertial sensors");
- }
- _singleton = this;
- AP_Param::setup_object_defaults(this, var_info);
- for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
- _gyro_cal_ok[i] = true;
- _accel_max_abs_offsets[i] = 3.5f;
- }
- for (uint8_t i=0; i<INS_VIBRATION_CHECK_INSTANCES; i++) {
- _accel_vibe_floor_filter[i].set_cutoff_frequency(AP_INERTIAL_SENSOR_ACCEL_VIBE_FLOOR_FILT_HZ);
- _accel_vibe_filter[i].set_cutoff_frequency(AP_INERTIAL_SENSOR_ACCEL_VIBE_FILT_HZ);
- }
- AP_AccelCal::register_client(this);
- }
- AP_InertialSensor *AP_InertialSensor::get_singleton()
- {
- if (!_singleton) {
- _singleton = new AP_InertialSensor();
- }
- return _singleton;
- }
- uint8_t AP_InertialSensor::register_gyro(uint16_t raw_sample_rate_hz,
- uint32_t id)
- {
- if (_gyro_count == INS_MAX_INSTANCES) {
- AP_HAL::panic("Too many gyros");
- }
- _gyro_raw_sample_rates[_gyro_count] = raw_sample_rate_hz;
- _gyro_over_sampling[_gyro_count] = 1;
- _gyro_raw_sampling_multiplier[_gyro_count] = INT16_MAX/radians(2000);
- bool saved = _gyro_id[_gyro_count].load();
- if (saved && (uint32_t)_gyro_id[_gyro_count] != id) {
-
- _gyro_cal_ok[_gyro_count] = false;
- }
- _gyro_id[_gyro_count].set((int32_t) id);
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- if (!saved) {
-
-
- _gyro_id[_gyro_count].save();
- }
- #endif
- return _gyro_count++;
- }
- uint8_t AP_InertialSensor::register_accel(uint16_t raw_sample_rate_hz,
- uint32_t id)
- {
- if (_accel_count == INS_MAX_INSTANCES) {
- AP_HAL::panic("Too many accels");
- }
- _accel_raw_sample_rates[_accel_count] = raw_sample_rate_hz;
- _accel_over_sampling[_accel_count] = 1;
- _accel_raw_sampling_multiplier[_accel_count] = INT16_MAX/(16*GRAVITY_MSS);
- bool saved = _accel_id[_accel_count].load();
- if (!saved) {
-
- _accel_id_ok[_accel_count] = false;
- } else if ((uint32_t)_accel_id[_accel_count] != id) {
-
- _accel_id_ok[_accel_count] = false;
- } else {
- _accel_id_ok[_accel_count] = true;
- }
- _accel_id[_accel_count].set((int32_t) id);
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
-
-
- _accel_id_ok[_accel_count] = true;
- _accel_id[_accel_count].save();
- #endif
- return _accel_count++;
- }
- void AP_InertialSensor::_start_backends()
- {
- detect_backends();
- for (uint8_t i = 0; i < _backend_count; i++) {
- _backends[i]->start();
- }
- if (_gyro_count == 0 || _accel_count == 0) {
- AP_HAL::panic("INS needs at least 1 gyro and 1 accel");
- }
-
- for (uint8_t i=get_accel_count(); i<INS_MAX_INSTANCES; i++) {
- _accel_id[i].set(0);
- }
- for (uint8_t i=get_gyro_count(); i<INS_MAX_INSTANCES; i++) {
- _gyro_id[i].set(0);
- }
- }
- AP_InertialSensor_Backend *AP_InertialSensor::_find_backend(int16_t backend_id, uint8_t instance)
- {
- assert(_backends_detected);
- uint8_t found = 0;
- for (uint8_t i = 0; i < _backend_count; i++) {
- int16_t id = _backends[i]->get_id();
- if (id < 0 || id != backend_id) {
- continue;
- }
- if (instance == found) {
- return _backends[i];
- } else {
- found++;
- }
- }
- return nullptr;
- }
- void
- AP_InertialSensor::init(uint16_t sample_rate)
- {
-
- _sample_rate = sample_rate;
- _loop_delta_t = 1.0f / sample_rate;
-
-
-
- _loop_delta_t_max = 10 * _loop_delta_t;
- if (_gyro_count == 0 && _accel_count == 0) {
- _start_backends();
- }
-
-
- for (uint8_t i=0; i<get_accel_count(); i++) {
- if (_accel_scale[i].get().is_zero()) {
- _accel_scale[i].set(Vector3f(1,1,1));
- }
- }
-
- if (gyro_calibration_timing() != GYRO_CAL_NEVER) {
- init_gyro();
- }
- _sample_period_usec = 1000*1000UL / _sample_rate;
-
- _delta_time = 0;
- _next_sample_usec = 0;
- _last_sample_usec = 0;
- _have_sample = false;
-
- batchsampler.init();
-
-
-
- _calculated_harmonic_notch_freq_hz = _harmonic_notch_filter.center_freq_hz();
- for (uint8_t i=0; i<get_gyro_count(); i++) {
- _gyro_harmonic_notch_filter[i].allocate_filters(_harmonic_notch_filter.harmonics());
-
- _gyro_harmonic_notch_filter[i].init(_gyro_raw_sample_rates[i], _calculated_harmonic_notch_freq_hz,
- _harmonic_notch_filter.bandwidth_hz(), _harmonic_notch_filter.attenuation_dB());
- }
- }
- bool AP_InertialSensor::_add_backend(AP_InertialSensor_Backend *backend)
- {
- if (!backend) {
- return false;
- }
- if (_backend_count == INS_MAX_BACKENDS) {
- AP_HAL::panic("Too many INS backends");
- }
- _backends[_backend_count++] = backend;
- return true;
- }
- void
- AP_InertialSensor::detect_backends(void)
- {
- if (_backends_detected) {
- return;
- }
- _backends_detected = true;
- #if defined(HAL_CHIBIOS_ARCH_CUBEBLACK)
-
-
-
-
-
-
-
-
- if (_use[0] == 1 && _use[1] == 1 && _use[2] == 0) {
- _use[2].set(1);
- }
- #endif
- uint8_t probe_count = 0;
- uint8_t enable_mask = uint8_t(_enable_mask.get());
- uint8_t found_mask = 0;
-
- #define ADD_BACKEND(x) do { \
- if (((1U<<probe_count)&enable_mask) && _add_backend(x)) { \
- found_mask |= (1U<<probe_count); \
- } \
- probe_count++; \
- } while (0)
- #define GET_I2C_DEVICE(bus, address) hal.i2c_mgr->get_device(bus, address)
- if (_hil_mode) {
- ADD_BACKEND(AP_InertialSensor_HIL::detect(*this));
- return;
- }
- #if defined(HAL_INS_PROBE_LIST)
-
- HAL_INS_PROBE_LIST;
- #elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
- ADD_BACKEND(AP_InertialSensor_SITL::detect(*this));
- #elif HAL_INS_DEFAULT == HAL_INS_HIL
- ADD_BACKEND(AP_InertialSensor_HIL::detect(*this));
- #elif AP_FEATURE_BOARD_DETECT
- switch (AP_BoardConfig::get_board_type()) {
- case AP_BoardConfig::PX4_BOARD_PX4V1:
- ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU60x0_NAME), ROTATION_NONE));
- break;
- case AP_BoardConfig::PX4_BOARD_PIXHAWK:
- ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU60x0_NAME), ROTATION_ROLL_180));
- ADD_BACKEND(AP_InertialSensor_LSM9DS0::probe(*this,
- hal.spi->get_device(HAL_INS_LSM9DS0_G_NAME),
- hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME),
- ROTATION_ROLL_180,
- ROTATION_ROLL_180_YAW_270,
- ROTATION_PITCH_180));
- break;
- case AP_BoardConfig::PX4_BOARD_PIXHAWK2:
-
- _fast_sampling_mask.set_default(1);
- ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_EXT_NAME), ROTATION_PITCH_180));
- ADD_BACKEND(AP_InertialSensor_LSM9DS0::probe(*this,
- hal.spi->get_device(HAL_INS_LSM9DS0_EXT_G_NAME),
- hal.spi->get_device(HAL_INS_LSM9DS0_EXT_A_NAME),
- ROTATION_ROLL_180_YAW_270,
- ROTATION_ROLL_180_YAW_90,
- ROTATION_ROLL_180_YAW_90));
- ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME), ROTATION_YAW_270));
-
- ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device("icm20602_ext"), ROTATION_ROLL_180_YAW_270));
- ADD_BACKEND(AP_InertialSensor_Invensensev2::probe(*this, hal.spi->get_device("icm20948_ext"), ROTATION_PITCH_180));
- ADD_BACKEND(AP_InertialSensor_Invensensev2::probe(*this, hal.spi->get_device("icm20948"), ROTATION_YAW_270));
- break;
- case AP_BoardConfig::PX4_BOARD_FMUV5:
- case AP_BoardConfig::PX4_BOARD_FMUV6:
- _fast_sampling_mask.set_default(1);
- ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device("icm20689"), ROTATION_NONE));
- ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device("icm20602"), ROTATION_NONE));
-
- ADD_BACKEND(AP_InertialSensor_BMI055::probe(*this,
- hal.spi->get_device("bmi055_a"),
- hal.spi->get_device("bmi055_g"),
- ROTATION_ROLL_180_YAW_90));
- ADD_BACKEND(AP_InertialSensor_BMI088::probe(*this,
- hal.spi->get_device("bmi055_a"),
- hal.spi->get_device("bmi055_g"),
- ROTATION_ROLL_180_YAW_90));
- break;
-
- case AP_BoardConfig::PX4_BOARD_SP01:
- _fast_sampling_mask.set_default(1);
- ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_EXT_NAME), ROTATION_NONE));
- ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME), ROTATION_NONE));
- break;
-
- case AP_BoardConfig::PX4_BOARD_PIXHAWK_PRO:
- _fast_sampling_mask.set_default(3);
- ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_ICM20608_NAME), ROTATION_ROLL_180_YAW_90));
- ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME), ROTATION_ROLL_180_YAW_90));
- break;
- case AP_BoardConfig::PX4_BOARD_PHMINI:
-
- _fast_sampling_mask.set_default(3);
- ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_ICM20608_AM_NAME), ROTATION_ROLL_180));
- ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME), ROTATION_ROLL_180));
- break;
- case AP_BoardConfig::PX4_BOARD_AUAV21:
-
- _fast_sampling_mask.set_default(3);
- ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_ICM20608_AM_NAME), ROTATION_ROLL_180_YAW_90));
- ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME), ROTATION_ROLL_180_YAW_90));
- break;
-
- case AP_BoardConfig::PX4_BOARD_PH2SLIM:
- _fast_sampling_mask.set_default(1);
- ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME), ROTATION_YAW_270));
- break;
- case AP_BoardConfig::PX4_BOARD_AEROFC:
- _fast_sampling_mask.set_default(1);
- ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU6500_NAME), ROTATION_YAW_270));
- break;
- case AP_BoardConfig::PX4_BOARD_MINDPXV2:
- ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU6500_NAME), ROTATION_NONE));
- ADD_BACKEND(AP_InertialSensor_LSM9DS0::probe(*this,
- hal.spi->get_device(HAL_INS_LSM9DS0_G_NAME),
- hal.spi->get_device(HAL_INS_LSM9DS0_A_NAME),
- ROTATION_YAW_90,
- ROTATION_YAW_90,
- ROTATION_YAW_90));
- break;
-
- case AP_BoardConfig::VRX_BOARD_BRAIN54:
- _fast_sampling_mask.set_default(7);
- ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU60x0_NAME), ROTATION_YAW_180));
- ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU60x0_EXT_NAME), ROTATION_YAW_180));
- #ifdef HAL_INS_MPU60x0_IMU_NAME
- ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU60x0_IMU_NAME), ROTATION_YAW_180));
- #endif
- break;
- case AP_BoardConfig::VRX_BOARD_BRAIN51:
- case AP_BoardConfig::VRX_BOARD_BRAIN52:
- case AP_BoardConfig::VRX_BOARD_BRAIN52E:
- case AP_BoardConfig::VRX_BOARD_CORE10:
- case AP_BoardConfig::VRX_BOARD_UBRAIN51:
- case AP_BoardConfig::VRX_BOARD_UBRAIN52:
- ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU60x0_NAME), ROTATION_YAW_180));
- break;
-
- case AP_BoardConfig::PX4_BOARD_PCNC1:
- _add_backend(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU60x0_NAME), ROTATION_ROLL_180));
- break;
- default:
- break;
- }
- #elif HAL_INS_DEFAULT == HAL_INS_NONE
-
- #else
- #error Unrecognised HAL_INS_TYPE setting
- #endif
- if (_backend_count == 0) {
- AP_BoardConfig::sensor_config_error("INS: unable to initialise driver");
- }
- }
- void AP_InertialSensor::periodic()
- {
- batchsampler.periodic();
- }
- bool AP_InertialSensor::_calculate_trim(const Vector3f &accel_sample, float& trim_roll, float& trim_pitch)
- {
- trim_pitch = atan2f(accel_sample.x, norm(accel_sample.y, accel_sample.z));
- trim_roll = atan2f(-accel_sample.y, -accel_sample.z);
- if (fabsf(trim_roll) > radians(10) ||
- fabsf(trim_pitch) > radians(10)) {
- hal.console->printf("trim over maximum of 10 degrees\n");
- return false;
- }
- hal.console->printf("Trim OK: roll=%.2f pitch=%.2f\n",
- (double)degrees(trim_roll),
- (double)degrees(trim_pitch));
- return true;
- }
- void
- AP_InertialSensor::init_gyro()
- {
- _init_gyro();
-
- _save_gyro_calibration();
- }
- uint32_t AP_InertialSensor::get_accel_clip_count(uint8_t instance) const
- {
- if (instance >= get_accel_count()) {
- return 0;
- }
- return _accel_clip_count[instance];
- }
- bool AP_InertialSensor::get_gyro_health_all(void) const
- {
- for (uint8_t i=0; i<get_gyro_count(); i++) {
- if (!get_gyro_health(i)) {
- return false;
- }
- }
-
- return (get_gyro_count() > 0);
- }
- bool AP_InertialSensor::gyro_calibrated_ok_all() const
- {
- for (uint8_t i=0; i<get_gyro_count(); i++) {
- if (!gyro_calibrated_ok(i)) {
- return false;
- }
- }
- for (uint8_t i=get_gyro_count(); i<INS_MAX_INSTANCES; i++) {
- if (_gyro_id[i] != 0) {
-
- return false;
- }
- }
- return (get_gyro_count() > 0);
- }
- bool AP_InertialSensor::use_gyro(uint8_t instance) const
- {
- if (instance >= INS_MAX_INSTANCES) {
- return false;
- }
- return (get_gyro_health(instance) && _use[instance]);
- }
- bool AP_InertialSensor::get_accel_health_all(void) const
- {
- for (uint8_t i=0; i<get_accel_count(); i++) {
- if (!get_accel_health(i)) {
- return false;
- }
- }
-
- return (get_accel_count() > 0);
- }
- bool AP_InertialSensor::calibrate_trim(float &trim_roll, float &trim_pitch)
- {
- Vector3f level_sample;
-
- if (_calibrating) {
- return false;
- }
- _calibrating = true;
- const uint8_t update_dt_milliseconds = (uint8_t)(1000.0f/get_sample_rate()+0.5f);
-
- for (uint8_t k=0; k<100/update_dt_milliseconds; k++) {
- wait_for_sample();
- update();
- hal.scheduler->delay(update_dt_milliseconds);
- }
- uint32_t num_samples = 0;
- while (num_samples < 400/update_dt_milliseconds) {
- wait_for_sample();
-
- update();
-
- Vector3f samp;
- samp = get_accel(0);
- level_sample += samp;
- if (!get_accel_health(0)) {
- goto failed;
- }
- hal.scheduler->delay(update_dt_milliseconds);
- num_samples++;
- }
- level_sample /= num_samples;
- if (!_calculate_trim(level_sample, trim_roll, trim_pitch)) {
- goto failed;
- }
- _calibrating = false;
- return true;
- failed:
- _calibrating = false;
- return false;
- }
- bool AP_InertialSensor::accel_calibrated_ok_all() const
- {
-
- if (_hil_mode) {
- return true;
- }
-
- for (uint8_t i=0; i<get_accel_count(); i++) {
- if (!_accel_id_ok[i]) {
- return false;
- }
-
- if (_accel_offset[i].get().is_zero()) {
- return false;
- }
-
- if (_accel_scale[i].get().is_zero()) {
- return false;
- }
- }
- for (uint8_t i=get_accel_count(); i<INS_MAX_INSTANCES; i++) {
- if (_accel_id[i] != 0) {
-
- return false;
- }
- }
-
-
- if (get_accel_count() < INS_MAX_INSTANCES) {
- for (uint8_t i=get_accel_count(); i<INS_MAX_INSTANCES; i++) {
- const Vector3f &scaling = _accel_scale[i].get();
- bool have_scaling = (!is_zero(scaling.x) && !is_equal(scaling.x,1.0f)) || (!is_zero(scaling.y) && !is_equal(scaling.y,1.0f)) || (!is_zero(scaling.z) && !is_equal(scaling.z,1.0f));
- bool have_offsets = !_accel_offset[i].get().is_zero();
- if (have_scaling || have_offsets) {
- return false;
- }
- }
- }
-
- return true;
- }
- bool AP_InertialSensor::use_accel(uint8_t instance) const
- {
- if (instance >= INS_MAX_INSTANCES) {
- return false;
- }
- return (get_accel_health(instance) && _use[instance]);
- }
- void
- AP_InertialSensor::_init_gyro()
- {
- uint8_t num_gyros = MIN(get_gyro_count(), INS_MAX_INSTANCES);
- Vector3f last_average[INS_MAX_INSTANCES], best_avg[INS_MAX_INSTANCES];
- Vector3f new_gyro_offset[INS_MAX_INSTANCES];
- float best_diff[INS_MAX_INSTANCES];
- bool converged[INS_MAX_INSTANCES];
-
- if (_calibrating) {
- return;
- }
-
- _calibrating = true;
-
- AP_Notify::flags.initialising = true;
-
- hal.console->printf("Init Gyro");
-
- enum Rotation saved_orientation = _board_orientation;
- _board_orientation = ROTATION_NONE;
-
- for (uint8_t k=0; k<num_gyros; k++) {
- _gyro_offset[k].set(Vector3f());
- new_gyro_offset[k].zero();
- best_diff[k] = -1.f;
- last_average[k].zero();
- converged[k] = false;
- }
- for(int8_t c = 0; c < 5; c++) {
- hal.scheduler->delay(5);
- update();
- }
-
-
-
- uint8_t num_converged = 0;
-
-
- for (int16_t j = 0; j <= 30*4 && num_converged < num_gyros; j++) {
- Vector3f gyro_sum[INS_MAX_INSTANCES], gyro_avg[INS_MAX_INSTANCES], gyro_diff[INS_MAX_INSTANCES];
- Vector3f accel_start;
- float diff_norm[INS_MAX_INSTANCES];
- uint8_t i;
- EXPECT_DELAY_MS(1000);
- memset(diff_norm, 0, sizeof(diff_norm));
- hal.console->printf("*");
- for (uint8_t k=0; k<num_gyros; k++) {
- gyro_sum[k].zero();
- }
- accel_start = get_accel(0);
- for (i=0; i<50; i++) {
- update();
- for (uint8_t k=0; k<num_gyros; k++) {
- gyro_sum[k] += get_gyro(k);
- }
- hal.scheduler->delay(5);
- }
- Vector3f accel_diff = get_accel(0) - accel_start;
- if (accel_diff.length() > 0.2f) {
-
-
-
-
- continue;
- }
- for (uint8_t k=0; k<num_gyros; k++) {
- gyro_avg[k] = gyro_sum[k] / i;
- gyro_diff[k] = last_average[k] - gyro_avg[k];
- diff_norm[k] = gyro_diff[k].length();
- }
- for (uint8_t k=0; k<num_gyros; k++) {
- if (best_diff[k] < 0) {
- best_diff[k] = diff_norm[k];
- best_avg[k] = gyro_avg[k];
- } else if (gyro_diff[k].length() < ToRad(GYRO_INIT_MAX_DIFF_DPS)) {
-
- last_average[k] = (gyro_avg[k] * 0.5f) + (last_average[k] * 0.5f);
- if (!converged[k] || last_average[k].length() < new_gyro_offset[k].length()) {
- new_gyro_offset[k] = last_average[k];
- }
- if (!converged[k]) {
- converged[k] = true;
- num_converged++;
- }
- } else if (diff_norm[k] < best_diff[k]) {
- best_diff[k] = diff_norm[k];
- best_avg[k] = (gyro_avg[k] * 0.5f) + (last_average[k] * 0.5f);
- }
- last_average[k] = gyro_avg[k];
- }
- }
-
-
- hal.console->printf("\n");
- for (uint8_t k=0; k<num_gyros; k++) {
- if (!converged[k]) {
- hal.console->printf("gyro[%u] did not converge: diff=%f dps (expected < %f)\n",
- (unsigned)k,
- (double)ToDeg(best_diff[k]),
- (double)GYRO_INIT_MAX_DIFF_DPS);
- _gyro_offset[k] = best_avg[k];
-
- _gyro_cal_ok[k] = false;
- } else {
- _gyro_cal_ok[k] = true;
- _gyro_offset[k] = new_gyro_offset[k];
- }
- }
-
- _board_orientation = saved_orientation;
-
- _calibrating = false;
-
- AP_Notify::flags.initialising = false;
- }
- void AP_InertialSensor::_save_gyro_calibration()
- {
- for (uint8_t i=0; i<_gyro_count; i++) {
- _gyro_offset[i].save();
- _gyro_id[i].save();
- }
- for (uint8_t i=_gyro_count; i<INS_MAX_INSTANCES; i++) {
- _gyro_offset[i].set_and_save(Vector3f());
- _gyro_id[i].set_and_save(0);
- }
- }
- void AP_InertialSensor::update(void)
- {
-
-
- wait_for_sample();
- if (!_hil_mode) {
- for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
-
-
-
- _gyro_healthy[i] = false;
- _accel_healthy[i] = false;
- _delta_velocity_valid[i] = false;
- _delta_angle_valid[i] = false;
- }
- for (uint8_t i=0; i<_backend_count; i++) {
- _backends[i]->update();
- }
-
- for (uint8_t i = 0; i < INS_MAX_INSTANCES; i++) {
- _delta_velocity_acc[i].zero();
- _delta_velocity_acc_dt[i] = 0;
- _delta_angle_acc[i].zero();
- _delta_angle_acc_dt[i] = 0;
- }
- if (!_startup_error_counts_set) {
- for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
- _accel_startup_error_count[i] = _accel_error_count[i];
- _gyro_startup_error_count[i] = _gyro_error_count[i];
- }
- if (_startup_ms == 0) {
- _startup_ms = AP_HAL::millis();
- } else if (AP_HAL::millis()-_startup_ms > 2000) {
- _startup_error_counts_set = true;
- }
- }
- for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
- if (_accel_error_count[i] < _accel_startup_error_count[i]) {
- _accel_startup_error_count[i] = _accel_error_count[i];
- }
- if (_gyro_error_count[i] < _gyro_startup_error_count[i]) {
- _gyro_startup_error_count[i] = _gyro_error_count[i];
- }
- }
-
-
- bool have_zero_accel_error_count = false;
- bool have_zero_gyro_error_count = false;
- for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
- if (_accel_healthy[i] && _accel_error_count[i] <= _accel_startup_error_count[i]) {
- have_zero_accel_error_count = true;
- }
- if (_gyro_healthy[i] && _gyro_error_count[i] <= _gyro_startup_error_count[i]) {
- have_zero_gyro_error_count = true;
- }
- }
- for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
- if (_gyro_healthy[i] && _gyro_error_count[i] > _gyro_startup_error_count[i] && have_zero_gyro_error_count) {
-
- _gyro_healthy[i] = false;
- }
- if (_accel_healthy[i] && _accel_error_count[i] > _accel_startup_error_count[i] && have_zero_accel_error_count) {
-
- _accel_healthy[i] = false;
- }
- }
-
- for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
- if (_gyro_healthy[i] && _use[i]) {
- _primary_gyro = i;
- break;
- }
- }
- for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
- if (_accel_healthy[i] && _use[i]) {
- _primary_accel = i;
- break;
- }
- }
- }
- _last_update_usec = AP_HAL::micros();
-
- _have_sample = false;
- }
- void AP_InertialSensor::wait_for_sample(void)
- {
- if (_have_sample) {
-
-
- return;
- }
- uint32_t now = AP_HAL::micros();
- if (_next_sample_usec == 0 && _delta_time <= 0) {
-
- _last_sample_usec = now - _sample_period_usec;
- _next_sample_usec = now + _sample_period_usec;
- goto check_sample;
- }
-
- if (_next_sample_usec - now <=_sample_period_usec) {
-
- uint32_t wait_usec = _next_sample_usec - now;
- hal.scheduler->delay_microseconds_boost(wait_usec);
- uint32_t now2 = AP_HAL::micros();
- if (now2+100 < _next_sample_usec) {
- timing_printf("shortsleep %u\n", (unsigned)(_next_sample_usec-now2));
- }
- if (now2 > _next_sample_usec+400) {
- timing_printf("longsleep %u wait_usec=%u\n",
- (unsigned)(now2-_next_sample_usec),
- (unsigned)wait_usec);
- }
- _next_sample_usec += _sample_period_usec;
- } else if (now - _next_sample_usec < _sample_period_usec/8) {
-
-
- timing_printf("overshoot1 %u\n", (unsigned)(now-_next_sample_usec));
- _next_sample_usec += _sample_period_usec;
- } else {
-
-
- timing_printf("overshoot2 %u\n", (unsigned)(now-_next_sample_usec));
- _next_sample_usec = now + _sample_period_usec;
- }
- check_sample:
- if (!_hil_mode) {
-
- uint8_t gyro_available_mask = 0;
- uint8_t accel_available_mask = 0;
- uint32_t wait_counter = 0;
- while (true) {
- for (uint8_t i=0; i<_backend_count; i++) {
-
-
- _backends[i]->accumulate();
- }
- for (uint8_t i=0; i<_gyro_count; i++) {
- if (_new_gyro_data[i]) {
- const uint8_t imask = (1U<<i);
- gyro_available_mask |= imask;
- if (_use[i]) {
- _gyro_wait_mask |= imask;
- } else {
- _gyro_wait_mask &= ~imask;
- }
- }
- }
- for (uint8_t i=0; i<_accel_count; i++) {
- if (_new_accel_data[i]) {
- const uint8_t imask = (1U<<i);
- accel_available_mask |= imask;
- if (_use[i]) {
- _accel_wait_mask |= imask;
- } else {
- _accel_wait_mask &= ~imask;
- }
- }
- }
-
-
-
- if (wait_counter < 7) {
- if (gyro_available_mask &&
- ((gyro_available_mask & _gyro_wait_mask) == _gyro_wait_mask) &&
- accel_available_mask &&
- ((accel_available_mask & _accel_wait_mask) == _accel_wait_mask)) {
- break;
- }
- } else {
- if (gyro_available_mask && accel_available_mask) {
-
-
-
- _gyro_wait_mask &= gyro_available_mask;
- _accel_wait_mask &= accel_available_mask;
- break;
- }
- }
- hal.scheduler->delay_microseconds_boost(100);
- wait_counter++;
- }
- }
- now = AP_HAL::micros();
- if (_hil_mode && _hil.delta_time > 0) {
- _delta_time = _hil.delta_time;
- _hil.delta_time = 0;
- } else {
- _delta_time = (now - _last_sample_usec) * 1.0e-6f;
- }
- _last_sample_usec = now;
- #if 0
- {
- static uint64_t delta_time_sum;
- static uint16_t counter;
- if (delta_time_sum == 0) {
- delta_time_sum = _sample_period_usec;
- }
- delta_time_sum += _delta_time * 1.0e6f;
- if (counter++ == 400) {
- counter = 0;
- hal.console->printf("now=%lu _delta_time_sum=%lu diff=%ld\n",
- (unsigned long)now,
- (unsigned long)delta_time_sum,
- (long)(now - delta_time_sum));
- }
- }
- #endif
- _have_sample = true;
- }
- bool AP_InertialSensor::get_delta_angle(uint8_t i, Vector3f &delta_angle) const
- {
- if (_delta_angle_valid[i]) {
- delta_angle = _delta_angle[i];
- return true;
- } else if (get_gyro_health(i)) {
-
-
- delta_angle = get_gyro(i) * get_delta_time();
- return true;
- }
- return false;
- }
- bool AP_InertialSensor::get_delta_velocity(uint8_t i, Vector3f &delta_velocity) const
- {
- if (_delta_velocity_valid[i]) {
- delta_velocity = _delta_velocity[i];
- return true;
- } else if (get_accel_health(i)) {
- delta_velocity = get_accel(i) * get_delta_time();
- return true;
- }
- return false;
- }
- float AP_InertialSensor::get_delta_velocity_dt(uint8_t i) const
- {
- float ret;
- if (_delta_velocity_valid[i]) {
- ret = _delta_velocity_dt[i];
- } else {
- ret = get_delta_time();
- }
- ret = MIN(ret, _loop_delta_t_max);
- return ret;
- }
- float AP_InertialSensor::get_delta_angle_dt(uint8_t i) const
- {
- float ret;
- if (_delta_angle_valid[i] && _delta_angle_dt[i] > 0) {
- ret = _delta_angle_dt[i];
- } else {
- ret = get_delta_time();
- }
- ret = MIN(ret, _loop_delta_t_max);
- return ret;
- }
- void AP_InertialSensor::set_accel(uint8_t instance, const Vector3f &accel)
- {
- if (_accel_count == 0) {
-
- return;
- }
- if (instance < INS_MAX_INSTANCES) {
- _accel[instance] = accel;
- _accel_healthy[instance] = true;
- if (_accel_count <= instance) {
- _accel_count = instance+1;
- }
- if (!_accel_healthy[_primary_accel]) {
- _primary_accel = instance;
- }
- }
- }
- void AP_InertialSensor::set_gyro(uint8_t instance, const Vector3f &gyro)
- {
- if (_gyro_count == 0) {
-
- return;
- }
- if (instance < INS_MAX_INSTANCES) {
- _gyro[instance] = gyro;
- _gyro_healthy[instance] = true;
- if (_gyro_count <= instance) {
- _gyro_count = instance+1;
- _gyro_cal_ok[instance] = true;
- }
- if (!_accel_healthy[_primary_accel]) {
- _primary_accel = instance;
- }
- }
- }
- void AP_InertialSensor::set_delta_time(float delta_time)
- {
- _hil.delta_time = delta_time;
- }
- void AP_InertialSensor::set_delta_velocity(uint8_t instance, float deltavt, const Vector3f &deltav)
- {
- if (instance < INS_MAX_INSTANCES) {
- _delta_velocity_valid[instance] = true;
- _delta_velocity[instance] = deltav;
- _delta_velocity_dt[instance] = deltavt;
- }
- }
- void AP_InertialSensor::set_delta_angle(uint8_t instance, const Vector3f &deltaa, float deltaat)
- {
- if (instance < INS_MAX_INSTANCES) {
- _delta_angle_valid[instance] = true;
- _delta_angle[instance] = deltaa;
- _delta_angle_dt[instance] = deltaat;
- }
- }
- AuxiliaryBus *AP_InertialSensor::get_auxiliary_bus(int16_t backend_id, uint8_t instance)
- {
- detect_backends();
- AP_InertialSensor_Backend *backend = _find_backend(backend_id, instance);
- if (backend == nullptr) {
- return nullptr;
- }
- return backend->get_auxiliary_bus();
- }
- void AP_InertialSensor::calc_vibration_and_clipping(uint8_t instance, const Vector3f &accel, float dt)
- {
-
- if (_backends[instance] == nullptr) {
- return;
- }
- if (fabsf(accel.x) > _backends[instance]->get_clip_limit() ||
- fabsf(accel.y) > _backends[instance]->get_clip_limit() ||
- fabsf(accel.z) > _backends[instance]->get_clip_limit()) {
- _accel_clip_count[instance]++;
- }
-
- if (instance < INS_VIBRATION_CHECK_INSTANCES) {
-
- Vector3f accel_filt = _accel_vibe_floor_filter[instance].apply(accel, dt);
-
- Vector3f accel_diff = (accel - accel_filt);
- accel_diff.x *= accel_diff.x;
- accel_diff.y *= accel_diff.y;
- accel_diff.z *= accel_diff.z;
- _accel_vibe_filter[instance].apply(accel_diff, dt);
- }
- }
- void AP_InertialSensor::set_accel_peak_hold(uint8_t instance, const Vector3f &accel)
- {
- if (instance != _primary_accel) {
-
- return;
- }
- uint32_t now = AP_HAL::millis();
-
- if (accel.x < _peak_hold_state.accel_peak_hold_neg_x ||
- _peak_hold_state.accel_peak_hold_neg_x_age <= now) {
- _peak_hold_state.accel_peak_hold_neg_x = accel.x;
- _peak_hold_state.accel_peak_hold_neg_x_age = now + AP_INERTIAL_SENSOR_ACCEL_PEAK_DETECT_TIMEOUT_MS;
- }
- }
- Vector3f AP_InertialSensor::get_vibration_levels(uint8_t instance) const
- {
- Vector3f vibe;
- if (instance < INS_VIBRATION_CHECK_INSTANCES) {
- vibe = _accel_vibe_filter[instance].get();
- vibe.x = safe_sqrt(vibe.x);
- vibe.y = safe_sqrt(vibe.y);
- vibe.z = safe_sqrt(vibe.z);
- }
- return vibe;
- }
- bool AP_InertialSensor::is_still()
- {
- Vector3f vibe = get_vibration_levels();
- return (vibe.x < _still_threshold) &&
- (vibe.y < _still_threshold) &&
- (vibe.z < _still_threshold);
- }
- void AP_InertialSensor::acal_init()
- {
-
- if (_acal == nullptr) {
- _acal = new AP_AccelCal;
- }
- if (_accel_calibrator == nullptr) {
- _accel_calibrator = new AccelCalibrator[INS_MAX_INSTANCES];
- }
- }
- void AP_InertialSensor::acal_update()
- {
- if(_acal == nullptr) {
- return;
- }
- EXPECT_DELAY_MS(20000);
- _acal->update();
- if (hal.util->get_soft_armed() && _acal->get_status() != ACCEL_CAL_NOT_STARTED) {
- _acal->cancel();
- }
- }
- void AP_InertialSensor::update_harmonic_notch_freq_hz(float scaled_freq) {
-
- if (is_positive(scaled_freq)) {
- _calculated_harmonic_notch_freq_hz = scaled_freq;
- }
- }
- void AP_InertialSensor::_acal_save_calibrations()
- {
- Vector3f bias, gain;
- for (uint8_t i=0; i<_accel_count; i++) {
- if (_accel_calibrator[i].get_status() == ACCEL_CAL_SUCCESS) {
- _accel_calibrator[i].get_calibration(bias, gain);
- _accel_offset[i].set_and_save(bias);
- _accel_scale[i].set_and_save(gain);
- _accel_id[i].save();
- _accel_id_ok[i] = true;
- } else {
- _accel_offset[i].set_and_save(Vector3f());
- _accel_scale[i].set_and_save(Vector3f());
- }
- }
-
- for (uint8_t i=_accel_count; i<INS_MAX_INSTANCES; i++) {
- _accel_id[i].set_and_save(0);
- _accel_offset[i].set_and_save(Vector3f());
- _accel_scale[i].set_and_save(Vector3f());
- }
-
- Vector3f aligned_sample;
- Vector3f misaligned_sample;
- switch(_trim_option) {
- case 0:
- break;
- case 1:
-
-
- get_primary_accel_cal_sample_avg(0,aligned_sample);
- _trim_pitch = atan2f(aligned_sample.x, norm(aligned_sample.y, aligned_sample.z));
- _trim_roll = atan2f(-aligned_sample.y, -aligned_sample.z);
- _new_trim = true;
- break;
- case 2:
-
-
- if (get_primary_accel_cal_sample_avg(0,misaligned_sample) && get_fixed_mount_accel_cal_sample(0,aligned_sample)) {
-
- Vector3f cross = (misaligned_sample%aligned_sample);
- float dot = (misaligned_sample*aligned_sample);
- Quaternion q(safe_sqrt(sq(misaligned_sample.length())*sq(aligned_sample.length()))+dot, cross.x, cross.y, cross.z);
- q.normalize();
- _trim_roll = q.get_euler_roll();
- _trim_pitch = q.get_euler_pitch();
- _new_trim = true;
- }
- break;
- default:
- _new_trim = false;
-
- }
- if (fabsf(_trim_roll) > radians(10) ||
- fabsf(_trim_pitch) > radians(10)) {
- hal.console->printf("ERR: Trim over maximum of 10 degrees!!");
- _new_trim = false;
- }
- _accel_cal_requires_reboot = true;
- }
- void AP_InertialSensor::_acal_event_failure()
- {
- for (uint8_t i=0; i<_accel_count; i++) {
- _accel_offset[i].set_and_notify(Vector3f(0,0,0));
- _accel_scale[i].set_and_notify(Vector3f(1,1,1));
- }
- }
- bool AP_InertialSensor::get_new_trim(float& trim_roll, float &trim_pitch)
- {
- if (_new_trim) {
- trim_roll = _trim_roll;
- trim_pitch = _trim_pitch;
- _new_trim = false;
- return true;
- }
- return false;
- }
- bool AP_InertialSensor::get_fixed_mount_accel_cal_sample(uint8_t sample_num, Vector3f& ret) const
- {
- if (_accel_count <= (_acc_body_aligned-1) || _accel_calibrator[2].get_status() != ACCEL_CAL_SUCCESS || sample_num>=_accel_calibrator[2].get_num_samples_collected()) {
- return false;
- }
- _accel_calibrator[_acc_body_aligned-1].get_sample_corrected(sample_num, ret);
- if (_board_orientation == ROTATION_CUSTOM && _custom_rotation) {
- ret = *_custom_rotation * ret;
- } else {
- ret.rotate(_board_orientation);
- }
- return true;
- }
- bool AP_InertialSensor::get_primary_accel_cal_sample_avg(uint8_t sample_num, Vector3f& ret) const
- {
- uint8_t count = 0;
- Vector3f avg = Vector3f(0,0,0);
- for (uint8_t i=0; i<MIN(_accel_count,2); i++) {
- if (_accel_calibrator[i].get_status() != ACCEL_CAL_SUCCESS || sample_num>=_accel_calibrator[i].get_num_samples_collected()) {
- continue;
- }
- Vector3f sample;
- _accel_calibrator[i].get_sample_corrected(sample_num, sample);
- avg += sample;
- count++;
- }
- if (count == 0) {
- return false;
- }
- avg /= count;
- ret = avg;
- if (_board_orientation == ROTATION_CUSTOM && _custom_rotation) {
- ret = *_custom_rotation * ret;
- } else {
- ret.rotate(_board_orientation);
- }
- return true;
- }
- MAV_RESULT AP_InertialSensor::simple_accel_cal()
- {
- uint8_t num_accels = MIN(get_accel_count(), INS_MAX_INSTANCES);
- Vector3f last_average[INS_MAX_INSTANCES];
- Vector3f new_accel_offset[INS_MAX_INSTANCES];
- Vector3f saved_offsets[INS_MAX_INSTANCES];
- Vector3f saved_scaling[INS_MAX_INSTANCES];
- bool converged[INS_MAX_INSTANCES];
- const float accel_convergence_limit = 0.05;
- Vector3f rotated_gravity(0, 0, -GRAVITY_MSS);
-
-
- if (_calibrating) {
- return MAV_RESULT_TEMPORARILY_REJECTED;
- }
- EXPECT_DELAY_MS(20000);
-
- _calibrating = true;
-
- AP_Notify::flags.initialising = true;
- hal.console->printf("Simple accel cal");
-
- enum Rotation saved_orientation = _board_orientation;
- _board_orientation = ROTATION_NONE;
-
- rotated_gravity.rotate_inverse(saved_orientation);
-
-
- for (uint8_t k=0; k<num_accels; k++) {
- saved_offsets[k] = _accel_offset[k];
- saved_scaling[k] = _accel_scale[k];
- }
-
-
- for (uint8_t k=0; k<num_accels; k++) {
- _accel_offset[k].set(Vector3f());
- _accel_scale[k].set(Vector3f(1,1,1));
- new_accel_offset[k].zero();
- last_average[k].zero();
- converged[k] = false;
- }
- for (uint8_t c = 0; c < 5; c++) {
- hal.scheduler->delay(5);
- update();
- }
-
-
-
- uint8_t num_converged = 0;
-
-
- for (int16_t j = 0; j <= 10*4 && num_converged < num_accels; j++) {
- Vector3f accel_sum[INS_MAX_INSTANCES], accel_avg[INS_MAX_INSTANCES], accel_diff[INS_MAX_INSTANCES];
- float diff_norm[INS_MAX_INSTANCES];
- uint8_t i;
- memset(diff_norm, 0, sizeof(diff_norm));
- hal.console->printf("*");
- for (uint8_t k=0; k<num_accels; k++) {
- accel_sum[k].zero();
- }
- for (i=0; i<50; i++) {
- update();
- for (uint8_t k=0; k<num_accels; k++) {
- accel_sum[k] += get_accel(k);
- }
- hal.scheduler->delay(5);
- }
- for (uint8_t k=0; k<num_accels; k++) {
- accel_avg[k] = accel_sum[k] / i;
- accel_diff[k] = last_average[k] - accel_avg[k];
- diff_norm[k] = accel_diff[k].length();
- }
- for (uint8_t k=0; k<num_accels; k++) {
- if (j > 0 && diff_norm[k] < accel_convergence_limit) {
- last_average[k] = (accel_avg[k] * 0.5f) + (last_average[k] * 0.5f);
- if (!converged[k] || last_average[k].length() < new_accel_offset[k].length()) {
- new_accel_offset[k] = last_average[k];
- }
- if (!converged[k]) {
- converged[k] = true;
- num_converged++;
- }
- } else {
- last_average[k] = accel_avg[k];
- }
- }
- }
- MAV_RESULT result = MAV_RESULT_ACCEPTED;
-
- for (uint8_t k=0; k<num_accels; k++) {
- if (!converged[k]) {
- result = MAV_RESULT_FAILED;
- }
- }
-
- _board_orientation = saved_orientation;
- if (result == MAV_RESULT_ACCEPTED) {
- hal.console->printf("\nPASSED\n");
- for (uint8_t k=0; k<num_accels; k++) {
-
- new_accel_offset[k] -= rotated_gravity;
- _accel_offset[k].set_and_save(new_accel_offset[k]);
- _accel_scale[k].save();
- _accel_id[k].save();
- _accel_id_ok[k] = true;
- }
-
- AP::ahrs().set_trim(Vector3f(0, 0, 0));
- } else {
- hal.console->printf("\nFAILED\n");
-
- for (uint8_t k=0; k<num_accels; k++) {
- _accel_offset[k] = saved_offsets[k];
- _accel_scale[k] = saved_scaling[k];
- }
- }
-
- _calibrating = false;
-
-
-
- uint32_t start_ms = AP_HAL::millis();
- while (AP_HAL::millis() - start_ms < 500) {
- update();
- }
-
- AP::ahrs().reset();
-
- AP_Notify::flags.initialising = false;
- return result;
- }
- AP_InertialSensor::Gyro_Calibration_Timing AP_InertialSensor::gyro_calibration_timing()
- {
- if (hal.util->was_watchdog_reset()) {
- return GYRO_CAL_NEVER;
- }
- return (Gyro_Calibration_Timing)_gyro_cal_timing.get();
- }
- #if !HAL_MINIMIZE_FEATURES
- void AP_InertialSensor::kill_imu(uint8_t imu_idx, bool kill_it)
- {
- if (kill_it) {
- uint8_t new_kill_mask = imu_kill_mask | (1U<<imu_idx);
-
- bool all_dead = true;
- for (uint8_t i=0; i<MIN(_gyro_count, _accel_count); i++) {
- if (use_gyro(i) && use_accel(i) && !(new_kill_mask & (1U<<i))) {
-
- all_dead = false;
- }
- }
- if (!all_dead) {
- imu_kill_mask = new_kill_mask;
- }
- } else {
- imu_kill_mask &= ~(1U<<imu_idx);
- }
- }
- #endif
- namespace AP {
- AP_InertialSensor &ins()
- {
- return *AP_InertialSensor::get_singleton();
- }
- };
|