Browse Source

DataFlash: use const ins reference

save some pointer dereferences
mission-4.1.18
Andrew Tridgell 11 years ago
parent
commit
4e82a8e1d4
  1. 2
      libraries/DataFlash/DataFlash.h
  2. 6
      libraries/DataFlash/LogFile.cpp

2
libraries/DataFlash/DataFlash.h

@ -46,7 +46,7 @@ public: @@ -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);

6
libraries/DataFlash/LogFile.cpp

@ -622,10 +622,10 @@ void DataFlash_Class::Log_Write_GPS(const GPS *gps, int32_t relative_alt) @@ -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,

Loading…
Cancel
Save