mirror of https://github.com/ArduPilot/ardupilot
DataFlash: fixes for INS API change
This commit is contained in:
parent
a0688a69d4
commit
a6b3d4217c
|
@ -708,10 +708,8 @@ 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;
|
||||||
}
|
}
|
||||||
Vector3f gyro;
|
const Vector3f &gyro = ins.get_gyro(1);
|
||||||
Vector3f accel;
|
const Vector3f &accel = ins.get_accel(1);
|
||||||
ins.get_gyro_instance(1, gyro);
|
|
||||||
ins.get_accel_instance(1, accel);
|
|
||||||
struct log_IMU pkt = {
|
struct log_IMU pkt = {
|
||||||
LOG_PACKET_HEADER_INIT(LOG_IMU2_MSG),
|
LOG_PACKET_HEADER_INIT(LOG_IMU2_MSG),
|
||||||
timestamp : hal.scheduler->millis(),
|
timestamp : hal.scheduler->millis(),
|
||||||
|
|
Loading…
Reference in New Issue