|
Firmware
|
Gyroscope calibration routine. More...
#include <px4_config.h>#include "gyro_calibration.h"#include "calibration_messages.h"#include "calibration_routines.h"#include "commander_helper.h"#include <px4_posix.h>#include <px4_defines.h>#include <px4_time.h>#include <stdio.h>#include <unistd.h>#include <fcntl.h>#include <poll.h>#include <cmath>#include <string.h>#include <drivers/drv_hrt.h>#include <uORB/topics/sensor_combined.h>#include <uORB/topics/sensor_correction.h>#include <drivers/drv_gyro.h>#include <systemlib/mavlink_log.h>#include <parameters/param.h>#include <systemlib/err.h>Classes | |
| struct | gyro_worker_data_t |
| Data passed to calibration worker routine. More... | |
Functions | |
| int | do_gyro_calibration (orb_advert_t *mavlink_log_pub) |
Gyroscope calibration routine.
| int do_gyro_calibration | ( | orb_advert_t * | mavlink_log_pub | ) |
< sensor thermal corrections
1.8.12