|
|
@ -687,11 +687,12 @@ void DataFlash_Class::Log_Write_RCOUT(void) |
|
|
|
// Write an raw accel/gyro data packet
|
|
|
|
// Write an raw accel/gyro data packet
|
|
|
|
void DataFlash_Class::Log_Write_IMU(const AP_InertialSensor &ins) |
|
|
|
void DataFlash_Class::Log_Write_IMU(const AP_InertialSensor &ins) |
|
|
|
{ |
|
|
|
{ |
|
|
|
|
|
|
|
uint32_t tstamp = hal.scheduler->millis(); |
|
|
|
const Vector3f &gyro = ins.get_gyro(); |
|
|
|
const Vector3f &gyro = ins.get_gyro(); |
|
|
|
const Vector3f &accel = ins.get_accel(); |
|
|
|
const Vector3f &accel = ins.get_accel(); |
|
|
|
struct log_IMU pkt = { |
|
|
|
struct log_IMU pkt = { |
|
|
|
LOG_PACKET_HEADER_INIT(LOG_IMU_MSG), |
|
|
|
LOG_PACKET_HEADER_INIT(LOG_IMU_MSG), |
|
|
|
timestamp : hal.scheduler->millis(), |
|
|
|
timestamp : tstamp, |
|
|
|
gyro_x : gyro.x, |
|
|
|
gyro_x : gyro.x, |
|
|
|
gyro_y : gyro.y, |
|
|
|
gyro_y : gyro.y, |
|
|
|
gyro_z : gyro.z, |
|
|
|
gyro_z : gyro.z, |
|
|
@ -700,27 +701,22 @@ void DataFlash_Class::Log_Write_IMU(const AP_InertialSensor &ins) |
|
|
|
accel_z : accel.z |
|
|
|
accel_z : accel.z |
|
|
|
}; |
|
|
|
}; |
|
|
|
WriteBlock(&pkt, sizeof(pkt)); |
|
|
|
WriteBlock(&pkt, sizeof(pkt)); |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// Write an raw accel/gyro data packet
|
|
|
|
|
|
|
|
void DataFlash_Class::Log_Write_IMU2(const AP_InertialSensor &ins) |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
if (ins.get_gyro_count() < 2 && ins.get_accel_count() < 2) { |
|
|
|
if (ins.get_gyro_count() < 2 && ins.get_accel_count() < 2) { |
|
|
|
return; |
|
|
|
return; |
|
|
|
} |
|
|
|
} |
|
|
|
const Vector3f &gyro = ins.get_gyro(1); |
|
|
|
const Vector3f &gyro2 = ins.get_gyro(); |
|
|
|
const Vector3f &accel = ins.get_accel(1); |
|
|
|
const Vector3f &accel2 = ins.get_accel(); |
|
|
|
struct log_IMU pkt = { |
|
|
|
struct log_IMU pkt2 = { |
|
|
|
LOG_PACKET_HEADER_INIT(LOG_IMU2_MSG), |
|
|
|
LOG_PACKET_HEADER_INIT(LOG_IMU2_MSG), |
|
|
|
timestamp : hal.scheduler->millis(), |
|
|
|
timestamp : tstamp, |
|
|
|
gyro_x : gyro.x, |
|
|
|
gyro_x : gyro2.x, |
|
|
|
gyro_y : gyro.y, |
|
|
|
gyro_y : gyro2.y, |
|
|
|
gyro_z : gyro.z, |
|
|
|
gyro_z : gyro2.z, |
|
|
|
accel_x : accel.x, |
|
|
|
accel_x : accel2.x, |
|
|
|
accel_y : accel.y, |
|
|
|
accel_y : accel2.y, |
|
|
|
accel_z : accel.z |
|
|
|
accel_z : accel2.z |
|
|
|
}; |
|
|
|
}; |
|
|
|
WriteBlock(&pkt, sizeof(pkt)); |
|
|
|
WriteBlock(&pkt2, sizeof(pkt2)); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// Write a text message to the log
|
|
|
|
// Write a text message to the log
|
|
|
|