58 unsigned int size,
unsigned int max_iterations,
float delta,
float *sphere_x,
float *sphere_y,
float *sphere_z,
59 float *sphere_radius);
60 int ellipsoid_fit_least_squares(
const float x[],
const float y[],
const float z[],
61 unsigned int size,
int max_iterations,
float delta,
float *offset_x,
float *offset_y,
float *offset_z,
62 float *sphere_radius,
float *diag_x,
float *diag_y,
float *diag_z,
float *offdiag_x,
float *offdiag_y,
64 int run_lm_sphere_fit(
const float x[],
const float y[],
const float z[],
float &_fitness,
float &_sphere_lambda,
65 unsigned int size,
float *offset_x,
float *offset_y,
float *offset_z,
66 float *sphere_radius,
float *diag_x,
float *diag_y,
float *diag_z,
float *offdiag_x,
float *offdiag_y,
68 int run_lm_ellipsoid_fit(
const float x[],
const float y[],
const float z[],
float &_fitness,
float &_sphere_lambda,
69 unsigned int size,
float *offset_x,
float *offset_y,
float *offset_z,
70 float *sphere_radius,
float *diag_x,
float *diag_y,
float *diag_z,
float *offdiag_x,
float *offdiag_y,
72 bool inverse4x4(
float m[],
float invOut[]);
73 bool mat_inverse(
float *A,
float *inv, uint8_t n);
76 static const unsigned max_accel_sens = 3;
79 enum detect_orientation_return {
80 DETECT_ORIENTATION_TAIL_DOWN,
81 DETECT_ORIENTATION_NOSE_DOWN,
82 DETECT_ORIENTATION_LEFT,
83 DETECT_ORIENTATION_RIGHT,
84 DETECT_ORIENTATION_UPSIDE_DOWN,
85 DETECT_ORIENTATION_RIGHTSIDE_UP,
86 DETECT_ORIENTATION_ERROR
88 static const unsigned detect_orientation_side_count = 6;
96 bool lenient_still_detection);
102 enum calibrate_return {
104 calibrate_return_error,
105 calibrate_return_cancelled
117 bool side_data_collected[detect_orientation_side_count],
120 bool lenient_still_detection);
140 #define calibration_log_info(_pub, _text, ...) \ 142 mavlink_and_console_log_info(_pub, _text, ##__VA_ARGS__); \ 146 #define calibration_log_critical(_pub, _text, ...) \ 148 mavlink_log_critical(_pub, _text, ##__VA_ARGS__); \ 152 #define calibration_log_emergency(_pub, _text, ...) \ 154 mavlink_log_emergency(_pub, _text, ##__VA_ARGS__); \ int sphere_fit_least_squares(const float x[], const float y[], const float z[], unsigned int size, unsigned int max_iterations, float delta, float *sphere_x, float *sphere_y, float *sphere_z, float *sphere_radius)
Least-squares fit of a sphere to a set of points.
Definition: calibration_routines.cpp:65
enum detect_orientation_return detect_orientation(orb_advert_t *mavlink_log_pub, int cancel_sub, int accel_sub, bool lenient_still_detection)
Wait for vehicle to become still and detect it's orientation.
Definition: calibration_routines.cpp:524
calibrate_return calibrate_from_orientation(orb_advert_t *mavlink_log_pub, int cancel_sub, bool side_data_collected[detect_orientation_side_count], calibration_from_orientation_worker_t calibration_worker, void *worker_data, bool lenient_still_detection)
Perform calibration sequence which require a rest orientation detection prior to calibration.
Definition: calibration_routines.cpp:683
void calibrate_cancel_unsubscribe(int cancel_sub)
Called to cancel the subscription to the cancel command.
Definition: calibration_routines.cpp:817
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
Definition: uORB.h:134
const char * detect_orientation_str(enum detect_orientation_return orientation)
Returns the human readable string representation of the orientation.
Definition: calibration_routines.cpp:668
calibrate_return(* calibration_from_orientation_worker_t)(detect_orientation_return orientation, int cancel_sub, void *worker_data)
Opaque worker data.
Definition: calibration_routines.h:108
bool calibrate_cancel_check(orb_advert_t *mavlink_log_pub, int cancel_sub)
Used to periodically check for a cancel command.
Definition: calibration_routines.cpp:839
int calibrate_cancel_subscribe(void)
Called at the beginning of calibration in order to subscribe to the cancel command.
Definition: calibration_routines.cpp:800