41 float declination_deg=0, inclination_deg=0, intensity_gauss=0;
61 diagonals.
x, offdiagonals.
x, offdiagonals.
y,
62 offdiagonals.
x, diagonals.
y, offdiagonals.
z,
63 offdiagonals.
y, offdiagonals.
z, diagonals.
z 72 errors[i] = intensity_gauss*1000;
101 DataFlash_Class::instance()->
Log_Write(
"COFS",
"TimeUS,OfsX,OfsY,OfsZ,Var,Yaw,WVar,N",
"QffffffI",
115 if (
num_samples > 30 && best_error < 50 && worst_error > 65) {
152 float bestv = 0, worstv=0;
179 const float learn_rate = 0.92;
181 errors[i] = errors[i] * learn_rate +
delta * (1-learn_rate);
185 if (i == 0 ||
errors[i] < bestv) {
190 if (i == 0 ||
errors[i] > worstv) {
bool get_soft_armed() const
Vector3< float > Vector3f
void set_learn_type(enum LearnType type, bool save)
CompassLearn(AP_AHRS &ahrs, Compass &compass)
virtual bool get_position(struct Location &loc) const =0
void from_euler(float roll, float pitch, float yaw)
virtual Semaphore * new_semaphore(void)
Matrix3< float > Matrix3f
void set_offsets(uint8_t i, const Vector3f &offsets)
int32_t lat
param 3 - Latitude * 10**7
const Vector3f & get_field(uint8_t i) const
Return the current field as a Vector3f in milligauss.
const Vector3f & get_diagonals(uint8_t i) const
virtual bool take_nonblocking() WARN_IF_UNUSED=0
float wrap_360(const T angle, float unit_mod)
void Log_Write(const char *name, const char *labels, const char *fmt,...)
void set_use_for_yaw(uint8_t i, bool use)
const Vector3f & get_offsets(uint8_t i) const
static DataFlash_Class * instance(void)
static const uint16_t num_sectors
enum LearnType get_learn_type(void) const
int32_t lng
param 4 - Longitude * 10**7
float wrap_2PI(const T radian)
static bool get_mag_field_ef(float latitude_deg, float longitude_deg, float &intensity_gauss, float &declination_deg, float &inclination_deg)
virtual void register_io_process(AP_HAL::MemberProc)=0
static constexpr float radians(float deg)
static const uint32_t min_field_change
uint32_t get_time_flying_ms(void) const
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
float errors[num_sectors]
void save_offsets(uint8_t i)
Vector3f predicted_offsets[num_sectors]
void process_sample(const struct sample &s)
AP_HAL::Scheduler * scheduler
const Vector3f & get_offdiagonals(uint8_t i) const