Path: blob/master/libraries/AP_Compass/AP_Compass_SITL.cpp
9365 views
#include "AP_Compass_SITL.h"12#if AP_COMPASS_SITL_ENABLED34#include <AP_HAL/AP_HAL.h>56extern const AP_HAL::HAL& hal;78AP_Compass_SITL::AP_Compass_SITL(uint8_t _sitl_instance) :9_sitl(AP::sitl()),10sitl_instance(_sitl_instance)11{12if (sitl_instance > ARRAY_SIZE(_sitl->mag_devid)) {13return;14}1516const uint32_t dev_id = _sitl->mag_devid[sitl_instance];17if (dev_id == 0) {18return;19}20if (!register_compass(dev_id)) {21return;22}23if (_sitl->mag_save_ids) {24// save so the compass always comes up configured in SITL25save_dev_id();26}27set_rotation(ROTATION_NONE);2829// Scroll through the registered compasses, and set the offsets30if (_compass.get_offsets(instance).is_zero()) {31_compass.set_offsets(instance, _sitl->mag_ofs[sitl_instance]);32}3334// we want to simulate a calibrated compass by default, so set35// scale to 136AP_Param::set_default_by_name("COMPASS_SCALE", 1);37AP_Param::set_default_by_name("COMPASS_SCALE2", 1);38AP_Param::set_default_by_name("COMPASS_SCALE3", 1);3940// make first compass external41if (sitl_instance == 0) {42set_external(true);43}4445hal.scheduler->register_timer_process(FUNCTOR_BIND(this, &AP_Compass_SITL::_timer, void));46}474849/*50create correction matrix for diagonals and off-diagonals51*/52void AP_Compass_SITL::_setup_eliptical_correcion()53{54Vector3f diag = _sitl->mag_diag[sitl_instance].get();55if (diag.is_zero()) {56diag = {1,1,1};57}58const Vector3f &diagonals = diag;59const Vector3f &offdiagonals = _sitl->mag_offdiag[sitl_instance];6061if (diagonals == _last_dia && offdiagonals == _last_odi) {62return;63}6465_eliptical_corr = Matrix3f(diagonals.x, offdiagonals.x, offdiagonals.y,66offdiagonals.x, diagonals.y, offdiagonals.z,67offdiagonals.y, offdiagonals.z, diagonals.z);68if (!_eliptical_corr.invert()) {69_eliptical_corr.identity();70}71_last_dia = diag;72_last_odi = offdiagonals;73}7475void AP_Compass_SITL::_timer()76{77// TODO: Refactor delay buffer with AP_Baro_SITL.7879// Sampled at 100Hz80uint32_t now = AP_HAL::millis();81if ((now - _last_sample_time) < 10) {82return;83}84_last_sample_time = now;8586// calculate sensor noise and add to 'truth' field in body frame87// units are milli-Gauss88Vector3f noise = rand_vec3f() * _sitl->mag_noise;89Vector3f new_mag_data = _sitl->state.bodyMagField + noise;9091// add delay92uint32_t best_time_delta = 1000; // initialise large time representing buffer entry closest to current time - delay.93uint8_t best_index = 0; // initialise number representing the index of the entry in buffer closest to delay.9495// storing data from sensor to buffer96if (now - last_store_time >= 10) { // store data every 10 ms.97last_store_time = now;98if (store_index > buffer_length-1) { // reset buffer index if index greater than size of buffer99store_index = 0;100}101buffer[store_index].data = new_mag_data; // add data to current index102buffer[store_index].time = last_store_time; // add time to current index103store_index = store_index + 1; // increment index104}105106// return delayed measurement107uint32_t delayed_time = now - _sitl->mag_delay; // get time corresponding to delay108// find data corresponding to delayed time in buffer109for (uint8_t i=0; i<=buffer_length-1; i++) {110// find difference between delayed time and time stamp in buffer111uint32_t time_delta = abs((int32_t)(delayed_time - buffer[i].time));112// if this difference is smaller than last delta, store this time113if (time_delta < best_time_delta) {114best_index= i;115best_time_delta = time_delta;116}117}118if (best_time_delta < 1000) { // only output stored state if < 1 sec retrieval error119new_mag_data = buffer[best_index].data;120}121122_setup_eliptical_correcion();123Vector3f f = (_eliptical_corr * new_mag_data) - _sitl->mag_ofs[sitl_instance].get();124// rotate compass125f.rotate_inverse((enum Rotation)_sitl->mag_orient[sitl_instance].get());126f.rotate(get_board_orientation());127// scale the compass to simulate sensor scale factor errors128f *= _sitl->mag_scaling[sitl_instance];129130switch (_sitl->mag_fail[sitl_instance]) {131case 0:132accumulate_sample(f, 10);133_last_data = f;134break;135case 1:136// no data137break;138case 2:139// frozen compass140accumulate_sample(_last_data, 10);141break;142}143}144145void AP_Compass_SITL::read()146{147drain_accumulated_samples(nullptr);148}149#endif // AP_COMPASS_SITL_ENABLED150151152