Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_AccelCal/AccelCalibrator.h
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.5This program is distributed in the hope that it will be useful,6but WITHOUT ANY WARRANTY; without even the implied warranty of7MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the8GNU General Public License for more details.9You should have received a copy of the GNU General Public License10along with this program. If not, see <http://www.gnu.org/licenses/>.11*/12#pragma once1314#include <AP_Math/AP_Math.h>15#include <AP_Math/vectorN.h>1617#define ACCEL_CAL_MAX_NUM_PARAMS 918#define ACCEL_CAL_TOLERANCE 0.119#define MAX_ITERATIONS 5020enum accel_cal_status_t {21ACCEL_CAL_NOT_STARTED=0,22ACCEL_CAL_WAITING_FOR_ORIENTATION=1,23ACCEL_CAL_COLLECTING_SAMPLE=2,24ACCEL_CAL_SUCCESS=3,25ACCEL_CAL_FAILED=426};2728enum accel_cal_fit_type_t {29ACCEL_CAL_AXIS_ALIGNED_ELLIPSOID=0,30ACCEL_CAL_ELLIPSOID=131};3233class AccelCalibrator {34public:35AccelCalibrator();3637//Select options, initialise variables and initiate accel calibration38void start(enum accel_cal_fit_type_t fit_type = ACCEL_CAL_AXIS_ALIGNED_ELLIPSOID, uint8_t num_samples = 6, float sample_time = 0.5f);39void start(enum accel_cal_fit_type_t fit_type, uint8_t num_samples, float sample_time, Vector3f offset, Vector3f diag, Vector3f offdiag);4041// set Accel calibrator status to make itself ready for future accel cals42void clear();4344// returns true if accel calibrator is running45bool running();4647// set Accel calibrator to start collecting samples in the next cycle48void collect_sample();4950// check if client's calibrator is active51void check_for_timeout();5253// get diag,offset or offdiag parameters as per the selected fitting surface or request54void get_calibration(Vector3f& offset) const;55void get_calibration(Vector3f& offset, Vector3f& diag) const;56void get_calibration(Vector3f& offset, Vector3f& diag, Vector3f& offdiag) const;575859// collect and avg sample to be passed onto LSQ estimator after all requisite orientations are done60void new_sample(const Vector3f& delta_velocity, float dt);6162// interface for LSq estimator to read sample buffer sent after conversion from delta velocity63// to averaged acc over time64bool get_sample(uint8_t i, Vector3f& s) const;6566// returns true and sample corrected with diag offdiag parameters as calculated by LSq estimation procedure67// returns false if no correct parameter exists to be applied along with existing sample without corrections68bool get_sample_corrected(uint8_t i, Vector3f& s) const;6970// set tolerance bar for parameter fitness value to cross so as to be deemed as correct values71void set_tolerance(float tolerance) { _conf_tolerance = tolerance; }7273// returns current state of accel calibrators74enum accel_cal_status_t get_status() const { return _status; }7576// returns number of samples collected77uint8_t get_num_samples_collected() const { return _samples_collected; }7879// returns mean squared fitness of sample points to the selected surface80float get_fitness() const { return _fitness; }8182struct param_t {83Vector3f offset;84Vector3f diag;85Vector3f offdiag;86};8788private:89struct AccelSample {90Vector3f delta_velocity;91float delta_time;92};93typedef VectorN<float, ACCEL_CAL_MAX_NUM_PARAMS> VectorP;9495union param_u {96struct param_t s;97VectorN<float, ACCEL_CAL_MAX_NUM_PARAMS> a;9899param_u() : a{}100{101static_assert(sizeof(*this) == sizeof(struct param_t),102"Invalid union members: sizes do not match");103}104};105106//configuration107uint8_t _conf_num_samples;108float _conf_sample_time;109enum accel_cal_fit_type_t _conf_fit_type;110float _conf_tolerance;111112// state113accel_cal_status_t _status;114struct AccelSample* _sample_buffer;115uint8_t _samples_collected;116union param_u _param;117float _fitness;118uint32_t _last_samp_frag_collected_ms;119float _min_sample_dist;120121// private methods122// check sanity of including the sample and add it to buffer if test is passed123bool accept_sample(const Vector3f& sample);124125// reset to calibrator state before the start of calibration126void reset_state();127128// sets status of calibrator and takes appropriate actions129void set_status(enum accel_cal_status_t);130131// determines if the result is acceptable132bool accept_result() const;133134// returns number of parameters are required for selected Fit type135uint8_t get_num_params() const;136137// Function related to Gauss Newton Least square regression process138float calc_residual(const Vector3f& sample, const struct param_t& params) const;139float calc_mean_squared_residuals(const struct param_t& params) const;140void calc_jacob(const Vector3f& sample, const struct param_t& params, VectorP& ret) const;141void run_fit(uint8_t max_iterations, float& fitness);142};143144145