From 0dc0e54767100e91cfa7e0931cfd9488373f56b7 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 16 May 2018 13:29:13 +1000 Subject: [PATCH] Copter: move Log_Write_Home_And_Origin into AP_AHRS --- ArduCopter/Copter.h | 1 - ArduCopter/Log.cpp | 18 +----------------- ArduCopter/commands.cpp | 4 ++-- 3 files changed, 3 insertions(+), 20 deletions(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index eceb5b3cef..3a8cdf75ce 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -806,7 +806,6 @@ private: void Log_Write_Data(uint8_t id, float value); void Log_Write_Error(uint8_t sub_system, uint8_t error_code); void Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, int16_t control_in, int16_t tune_low, int16_t tune_high); - void Log_Write_Home_And_Origin(); void Log_Sensor_Health(); #if FRAME_CONFIG == HELI_FRAME void Log_Write_Heli(void); diff --git a/ArduCopter/Log.cpp b/ArduCopter/Log.cpp index 6bceaef90f..cd0f3d4303 100644 --- a/ArduCopter/Log.cpp +++ b/ArduCopter/Log.cpp @@ -361,21 +361,6 @@ void Copter::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, int16_t DataFlash.WriteBlock(&pkt_tune, sizeof(pkt_tune)); } -// log EKF origin and ahrs home to dataflash -void Copter::Log_Write_Home_And_Origin() -{ - // log ekf origin if set - Location ekf_orig; - if (ahrs.get_origin(ekf_orig)) { - DataFlash.Log_Write_Origin(LogOriginType::ekf_origin, ekf_orig); - } - - // log ahrs home if set - if (ahrs.home_is_set()) { - DataFlash.Log_Write_Origin(LogOriginType::ahrs_home, ahrs.get_home()); - } -} - // logs when baro or compass becomes unhealthy void Copter::Log_Sensor_Health() { @@ -544,7 +529,7 @@ void Copter::Log_Write_Vehicle_Startup_Messages() #if AC_RALLY DataFlash.Log_Write_Rally(rally); #endif - Log_Write_Home_And_Origin(); + ahrs.Log_Write_Home_And_Origin(); gps.Write_DataFlash_Log_Startup_messages(); } @@ -569,7 +554,6 @@ void Copter::Log_Write_Data(uint8_t id, uint16_t value) {} void Copter::Log_Write_Data(uint8_t id, float value) {} void Copter::Log_Write_Error(uint8_t sub_system, uint8_t error_code) {} void Copter::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, int16_t control_in, int16_t tune_low, int16_t tune_high) {} -void Copter::Log_Write_Home_And_Origin() {} void Copter::Log_Sensor_Health() {} void Copter::Log_Write_Precland() {} void Copter::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target) {} diff --git a/ArduCopter/commands.cpp b/ArduCopter/commands.cpp index 08b04fec61..56e95c1fde 100644 --- a/ArduCopter/commands.cpp +++ b/ArduCopter/commands.cpp @@ -100,7 +100,7 @@ bool Copter::set_home(const Location& loc, bool lock) } // log ahrs home and ekf origin dataflash - Log_Write_Home_And_Origin(); + ahrs.Log_Write_Home_And_Origin(); // send new home and ekf origin to GCS gcs().send_home(loc); @@ -130,7 +130,7 @@ void Copter::set_ekf_origin(const Location& loc) } // log ahrs home and ekf origin dataflash - Log_Write_Home_And_Origin(); + ahrs.Log_Write_Home_And_Origin(); // send ekf origin to GCS gcs().send_ekf_origin(loc);