diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index fd9b2e4c15..1570888c30 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -4,7 +4,7 @@ // valid! You should switch to using a HAL_BOARD flag in your local config.mk. // uncomment the lines below to disable features (flash sizes listed are for APM2 boards and will underestimate savings on Pixhawk and other boards) -//#define LOGGING_ENABLED DISABLED // disable dataflash logging to save 11K of flash space +//#define LOGGING_ENABLED DISABLED // disable logging to save 11K of flash space //#define MOUNT DISABLED // disable the camera gimbal to save 8K of flash space //#define AUTOTUNE_ENABLED DISABLED // disable the auto tune functionality to save 7k of flash //#define AC_FENCE DISABLED // disable fence to save 2k of flash diff --git a/ArduCopter/ArduCopter.cpp b/ArduCopter/ArduCopter.cpp index a468eb952f..f1e12f57ae 100644 --- a/ArduCopter/ArduCopter.cpp +++ b/ArduCopter/ArduCopter.cpp @@ -492,7 +492,7 @@ void Copter::init_simple_bearing() super_simple_cos_yaw = simple_cos_yaw; super_simple_sin_yaw = simple_sin_yaw; - // log the simple bearing to dataflash + // log the simple bearing if (should_log(MASK_LOG_ANY)) { Log_Write_Data(DATA_INIT_SIMPLE_BEARING, ahrs.yaw_sensor); } @@ -571,7 +571,6 @@ void Copter::update_altitude() // read in baro altitude read_barometer(); - // write altitude info to dataflash logs if (should_log(MASK_LOG_CTUN)) { Log_Write_Control_Tuning(); } diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 71aa0c2a12..960bc96489 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -224,7 +224,6 @@ private: RC_Channel *channel_throttle; RC_Channel *channel_yaw; - // Dataflash AP_Logger logger; AP_GPS gps; @@ -292,7 +291,7 @@ private: uint8_t pre_arm_rc_check : 1; // 3 // true if rc input pre-arm checks have been completed successfully uint8_t pre_arm_check : 1; // 4 // true if all pre-arm checks (rc, accel calibration, gps lock) have been performed uint8_t auto_armed : 1; // 5 // stops auto missions from beginning until throttle is raised - uint8_t logging_started : 1; // 6 // true if dataflash logging has started + uint8_t logging_started : 1; // 6 // true if logging has started uint8_t land_complete : 1; // 7 // true if we have detected a landing uint8_t new_radio_frame : 1; // 8 // Set true if we have new PWM data to act on from the Radio uint8_t usb_connected_unused : 1; // 9 // UNUSED diff --git a/ArduCopter/avoidance_adsb.cpp b/ArduCopter/avoidance_adsb.cpp index 452f1d179f..73f6ba7dd7 100644 --- a/ArduCopter/avoidance_adsb.cpp +++ b/ArduCopter/avoidance_adsb.cpp @@ -88,7 +88,6 @@ MAV_COLLISION_ACTION AP_Avoidance_Copter::handle_avoidance(const AP_Avoidance::O } } - // log to dataflash if (failsafe_state_change) { AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_ADSB, LogErrorCode(actual_action)); diff --git a/ArduCopter/config.h b/ArduCopter/config.h index a8cba6e81e..0b250ef0c2 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -623,7 +623,7 @@ #endif ////////////////////////////////////////////////////////////////////////////// -// Dataflash logging control +// Logging control // #ifndef LOGGING_ENABLED # define LOGGING_ENABLED ENABLED diff --git a/ArduCopter/crash_check.cpp b/ArduCopter/crash_check.cpp index c10792d7ab..c9dcdd1f4d 100644 --- a/ArduCopter/crash_check.cpp +++ b/ArduCopter/crash_check.cpp @@ -47,7 +47,6 @@ void Copter::crash_check() // check if crashing for 2 seconds if (crash_counter >= (CRASH_CHECK_TRIGGER_SEC * scheduler.get_loop_rate_hz())) { - // log an error in the dataflash AP::logger().Write_Error(LogErrorSubsystem::CRASH_CHECK, LogErrorCode::CRASH_CHECK_CRASH); // keep logging even if disarmed: AP::logger().set_force_log_disarmed(true); @@ -115,7 +114,6 @@ void Copter::thrust_loss_check() if (thrust_loss_counter >= (THRUST_LOSS_CHECK_TRIGGER_SEC * scheduler.get_loop_rate_hz())) { // reset counter thrust_loss_counter = 0; - // log an error in the dataflash AP::logger().Write_Error(LogErrorSubsystem::THRUST_LOSS_CHECK, LogErrorCode::FAILSAFE_OCCURRED); // send message to gcs gcs().send_text(MAV_SEVERITY_EMERGENCY, "Potential Thrust Loss (%d)", (int)motors->get_lost_motor() + 1); @@ -199,7 +197,6 @@ void Copter::parachute_check() } else if (control_loss_count >= (PARACHUTE_CHECK_TRIGGER_SEC*scheduler.get_loop_rate_hz())) { // reset control loss counter control_loss_count = 0; - // log an error in the dataflash AP::logger().Write_Error(LogErrorSubsystem::CRASH_CHECK, LogErrorCode::CRASH_CHECK_LOSS_OF_CONTROL); // release parachute parachute_release(); @@ -233,7 +230,6 @@ void Copter::parachute_manual_release() if (ap.land_complete) { // warn user of reason for failure gcs().send_text(MAV_SEVERITY_INFO,"Parachute: Landed"); - // log an error in the dataflash AP::logger().Write_Error(LogErrorSubsystem::PARACHUTES, LogErrorCode::PARACHUTE_LANDED); return; } @@ -242,7 +238,6 @@ void Copter::parachute_manual_release() if ((parachute.alt_min() != 0 && (current_loc.alt < (int32_t)parachute.alt_min() * 100))) { // warn user of reason for failure gcs().send_text(MAV_SEVERITY_ALERT,"Parachute: Too low"); - // log an error in the dataflash AP::logger().Write_Error(LogErrorSubsystem::PARACHUTES, LogErrorCode::PARACHUTE_TOO_LOW); return; } diff --git a/ArduCopter/ekf_check.cpp b/ArduCopter/ekf_check.cpp index bd9fcd9c8d..d6d1900728 100644 --- a/ArduCopter/ekf_check.cpp +++ b/ArduCopter/ekf_check.cpp @@ -54,7 +54,6 @@ void Copter::ekf_check() // limit count from climbing too high ekf_check_state.fail_count = EKF_CHECK_ITERATIONS_MAX; ekf_check_state.bad_variance = true; - // log an error in the dataflash AP::logger().Write_Error(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_BAD_VARIANCE); // send message to gcs if ((AP_HAL::millis() - ekf_check_state.last_warn_time) > EKF_CHECK_WARNING_TIME) { @@ -72,7 +71,6 @@ void Copter::ekf_check() // if compass is flagged as bad and the counter reaches zero then clear flag if (ekf_check_state.bad_variance && ekf_check_state.fail_count == 0) { ekf_check_state.bad_variance = false; - // log recovery in the dataflash AP::logger().Write_Error(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_VARIANCE_CLEARED); // clear failsafe failsafe_ekf_off_event(); @@ -173,7 +171,6 @@ void Copter::failsafe_ekf_off_event(void) return; } - // clear flag and log recovery failsafe.ekf = false; AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_RESOLVED); } diff --git a/ArduCopter/events.cpp b/ArduCopter/events.cpp index b3e00905f1..810375b54d 100644 --- a/ArduCopter/events.cpp +++ b/ArduCopter/events.cpp @@ -35,7 +35,6 @@ void Copter::failsafe_radio_on_event() } } - // log the error to the dataflash AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_RADIO, LogErrorCode::FAILSAFE_OCCURRED); } @@ -116,7 +115,6 @@ void Copter::failsafe_gcs_check() } // GCS failsafe event has occurred - // update state, log to dataflash set_failsafe_gcs(true); AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_GCS, LogErrorCode::FAILSAFE_OCCURRED); @@ -141,7 +139,6 @@ void Copter::failsafe_gcs_check() // failsafe_gcs_off_event - actions to take when GCS contact is restored void Copter::failsafe_gcs_off_event(void) { - // log recovery of GCS in logs? AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_GCS, LogErrorCode::FAILSAFE_RESOLVED); } diff --git a/ArduCopter/failsafe.cpp b/ArduCopter/failsafe.cpp index b68bbcc153..c3ee045c88 100644 --- a/ArduCopter/failsafe.cpp +++ b/ArduCopter/failsafe.cpp @@ -57,7 +57,7 @@ void Copter::failsafe_check() if (motors->armed()) { motors->output_min(); } - // log an error + AP::logger().Write_Error(LogErrorSubsystem::CPU, LogErrorCode::FAILSAFE_OCCURRED); } diff --git a/ArduCopter/fence.cpp b/ArduCopter/fence.cpp index e69f109e2e..f7e0ebb886 100644 --- a/ArduCopter/fence.cpp +++ b/ArduCopter/fence.cpp @@ -69,7 +69,6 @@ void Copter::fence_check() } } - // log an error in the dataflash AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode(new_breaches)); } else if (orig_breaches) { diff --git a/ArduCopter/mode_rtl.cpp b/ArduCopter/mode_rtl.cpp index c7a082c655..10ebd4c2b5 100644 --- a/ArduCopter/mode_rtl.cpp +++ b/ArduCopter/mode_rtl.cpp @@ -22,7 +22,6 @@ bool Copter::ModeRTL::init(bool ignore_checks) // re-start RTL with terrain following disabled void Copter::ModeRTL::restart_without_terrain() { - // log an error AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::RESTARTED_RTL); if (rtl_path.terrain_used) { build_path(false); diff --git a/ArduCopter/motors.cpp b/ArduCopter/motors.cpp index 03403b4bbc..d6061452ba 100644 --- a/ArduCopter/motors.cpp +++ b/ArduCopter/motors.cpp @@ -156,7 +156,7 @@ bool Copter::init_arm_motors(const AP_Arming::Method method, const bool do_armin return false; } - // let dataflash know that we're armed (it may open logs e.g.) + // let logger know that we're armed (it may open logs e.g.) AP::logger().set_vehicle_armed(true); // disable cpu failsafe because initialising everything takes a while @@ -217,7 +217,6 @@ bool Copter::init_arm_motors(const AP_Arming::Method method, const bool do_armin // finally actually arm the motors motors->armed(true); - // log arming to dataflash Log_Write_Event(DATA_ARMED); // log flight mode in case it was changed while vehicle was disarmed @@ -276,7 +275,6 @@ void Copter::init_disarm_motors() set_land_complete(true); set_land_complete_maybe(true); - // log disarm to the dataflash Log_Write_Event(DATA_DISARMED); // send disarm command to motors