#include "AP_InertialSensor.h" #include "AP_InertialSensor_Backend.h" #include // Write ACC data packet: raw accel data void AP_InertialSensor_Backend::Write_ACC(const uint8_t instance, const uint64_t sample_us, const Vector3f &accel) const { const uint64_t now = AP_HAL::micros64(); const struct log_ACC pkt { LOG_PACKET_HEADER_INIT(LOG_ACC_MSG), time_us : now, instance : instance, sample_us : sample_us?sample_us:now, AccX : accel.x, AccY : accel.y, AccZ : accel.z }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); } // Write GYR data packet: raw gyro data void AP_InertialSensor_Backend::Write_GYR(const uint8_t instance, const uint64_t sample_us, const Vector3f &gyro) const { const uint64_t now = AP_HAL::micros64(); const struct log_GYR pkt{ LOG_PACKET_HEADER_INIT(LOG_GYR_MSG), time_us : now, instance : instance, sample_us : sample_us?sample_us:now, GyrX : gyro.x, GyrY : gyro.y, GyrZ : gyro.z }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); } // Write IMU data packet: raw accel/gyro data void AP_InertialSensor::Write_IMU_instance(const uint64_t time_us, const uint8_t imu_instance) const { const Vector3f &gyro = get_gyro(imu_instance); const Vector3f &accel = get_accel(imu_instance); const struct log_IMU pkt{ LOG_PACKET_HEADER_INIT(LOG_IMU_MSG), time_us : time_us, instance: imu_instance, gyro_x : gyro.x, gyro_y : gyro.y, gyro_z : gyro.z, accel_x : accel.x, accel_y : accel.y, accel_z : accel.z, gyro_error : get_gyro_error_count(imu_instance), accel_error : get_accel_error_count(imu_instance), temperature : get_temperature(imu_instance), gyro_health : (uint8_t)get_gyro_health(imu_instance), accel_health : (uint8_t)get_accel_health(imu_instance), gyro_rate : get_gyro_rate_hz(imu_instance), accel_rate : get_accel_rate_hz(imu_instance), }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); } // Write IMU data packet for all instances void AP_InertialSensor::Write_IMU() const { const uint64_t time_us = AP_HAL::micros64(); uint8_t n = MAX(get_accel_count(), get_gyro_count()); for (uint8_t i=0; i