diff --git a/APMrover2/Log.cpp b/APMrover2/Log.cpp index dcbfbbcb64..c3a218e839 100644 --- a/APMrover2/Log.cpp +++ b/APMrover2/Log.cpp @@ -166,7 +166,8 @@ struct PACKED log_Arm_Disarm { uint16_t arm_checks; }; -void Rover::Log_Arm_Disarm() { +void Rover::Log_Write_Arm_Disarm() +{ struct log_Arm_Disarm pkt = { LOG_PACKET_HEADER_INIT(LOG_ARM_DISARM_MSG), time_us : AP_HAL::micros64(), @@ -322,7 +323,7 @@ void Rover::Log_Write_Rangefinder() {} void Rover::Log_Write_Attitude() {} void Rover::Log_Write_RC(void) {} void Rover::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target) {} -void Rover::Log_Arm_Disarm() {} +void Rover::Log_Write_Arm_Disarm() {} void Rover::Log_Write_Error(uint8_t sub_system, uint8_t error_code) {} void Rover::Log_Write_Steering() {} void Rover::Log_Write_WheelEncoder() {} diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 4b1605efca..5d58cfbf7f 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -482,7 +482,7 @@ private: void Log_Write_Nav_Tuning(); void Log_Write_Attitude(); void Log_Write_Rangefinder(); - void Log_Arm_Disarm(); + void Log_Write_Arm_Disarm(); void Log_Write_RC(void); void Log_Write_Error(uint8_t sub_system, uint8_t error_code); void Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target); diff --git a/APMrover2/system.cpp b/APMrover2/system.cpp index 2719cc302e..6e4955942b 100644 --- a/APMrover2/system.cpp +++ b/APMrover2/system.cpp @@ -337,7 +337,7 @@ bool Rover::should_log(uint32_t mask) */ void Rover::change_arm_state(void) { - Log_Arm_Disarm(); + Log_Write_Arm_Disarm(); update_soft_armed(); }