From 4e82a8e1d4198eb652894966fdd6d7d907290946 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 4 Nov 2013 14:36:14 +1100 Subject: [PATCH] DataFlash: use const ins reference save some pointer dereferences --- libraries/DataFlash/DataFlash.h | 2 +- libraries/DataFlash/LogFile.cpp | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/DataFlash/DataFlash.h b/libraries/DataFlash/DataFlash.h index b051d9111d..da00563471 100644 --- a/libraries/DataFlash/DataFlash.h +++ b/libraries/DataFlash/DataFlash.h @@ -46,7 +46,7 @@ public: void Log_Write_Format(const struct LogStructure *structure); void Log_Write_Parameter(const char *name, float value); void Log_Write_GPS(const GPS *gps, int32_t relative_alt); - void Log_Write_IMU(const AP_InertialSensor *ins); + void Log_Write_IMU(const AP_InertialSensor &ins); void Log_Write_Message(const char *message); void Log_Write_Message_P(const prog_char_t *message); diff --git a/libraries/DataFlash/LogFile.cpp b/libraries/DataFlash/LogFile.cpp index e63d33a934..f28d3b3409 100644 --- a/libraries/DataFlash/LogFile.cpp +++ b/libraries/DataFlash/LogFile.cpp @@ -622,10 +622,10 @@ void DataFlash_Class::Log_Write_GPS(const GPS *gps, int32_t relative_alt) // 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) { - Vector3f gyro = ins->get_gyro(); - Vector3f accel = ins->get_accel(); + Vector3f gyro = ins.get_gyro(); + Vector3f accel = ins.get_accel(); struct log_IMU pkt = { LOG_PACKET_HEADER_INIT(LOG_IMU_MSG), gyro_x : gyro.x,