From a6b3d4217c05a6047e6d5ae47ccc377a071f1887 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 9 Dec 2013 09:50:29 +1100 Subject: [PATCH] DataFlash: fixes for INS API change --- libraries/DataFlash/LogFile.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/libraries/DataFlash/LogFile.cpp b/libraries/DataFlash/LogFile.cpp index 753b9cf9b5..856102d9ee 100644 --- a/libraries/DataFlash/LogFile.cpp +++ b/libraries/DataFlash/LogFile.cpp @@ -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) { return; } - Vector3f gyro; - Vector3f accel; - ins.get_gyro_instance(1, gyro); - ins.get_accel_instance(1, accel); + const Vector3f &gyro = ins.get_gyro(1); + const Vector3f &accel = ins.get_accel(1); struct log_IMU pkt = { LOG_PACKET_HEADER_INIT(LOG_IMU2_MSG), timestamp : hal.scheduler->millis(),