Sub: rename dataflash to logger

This commit is contained in:
Tom Pittenger 2019-02-11 00:11:57 -08:00 committed by Peter Barker
parent 7030dbc766
commit 2dc766556d
7 changed files with 4 additions and 12 deletions

View File

@ -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 AC_FENCE DISABLED // disable fence to save 2k of flash
//#define CAMERA DISABLED // disable camera trigger to save 1k of flash

View File

@ -336,7 +336,6 @@ void Sub::update_altitude()
// read in baro altitude
read_barometer();
// write altitude info to dataflash logs
if (should_log(MASK_LOG_CTUN)) {
Log_Write_Control_Tuning();
}

View File

@ -166,7 +166,6 @@ private:
RC_Channel *channel_forward;
RC_Channel *channel_lateral;
// Dataflash
AP_Logger logger;
AP_GPS gps;
@ -229,7 +228,7 @@ private:
union {
struct {
uint8_t pre_arm_check : 1; // true if all pre-arm checks (rc, accel calibration, gps lock) have been performed
uint8_t logging_started : 1; // true if dataflash logging has started
uint8_t logging_started : 1; // true if logging has started
uint8_t compass_mot : 1; // true if we are currently performing compassmot calibration
uint8_t motor_test : 1; // true if we are currently performing the motors test
uint8_t initialised : 1; // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes

View File

@ -259,7 +259,7 @@
#endif
//////////////////////////////////////////////////////////////////////////////
// Dataflash logging control
// Logging control
//
#ifndef LOGGING_ENABLED
# define LOGGING_ENABLED ENABLED

View File

@ -51,7 +51,6 @@ void Sub::mainloop_failsafe_check()
if (motors.armed()) {
motors.output_min();
}
// log an error
AP::logger().Write_Error(LogErrorSubsystem::CPU,LogErrorCode::FAILSAFE_OCCURRED);
}
@ -341,7 +340,6 @@ void Sub::failsafe_gcs_check()
return;
}
// update state, log to dataflash
failsafe.gcs = true;
AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_GCS, LogErrorCode::FAILSAFE_OCCURRED);
@ -409,7 +407,6 @@ void Sub::failsafe_crash_check()
}
failsafe.crash = true;
// log an error in the dataflash
AP::logger().Write_Error(LogErrorSubsystem::CRASH_CHECK, LogErrorCode::CRASH_CHECK_CRASH);
// disarm motors

View File

@ -41,7 +41,6 @@ void Sub::fence_check()
// }
}
// log an error in the dataflash
AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode(new_breaches));
} else if (orig_breaches) {
// record clearing of breach

View File

@ -25,7 +25,7 @@ bool Sub::init_arm_motors(AP_Arming::Method method)
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
@ -67,7 +67,6 @@ bool Sub::init_arm_motors(AP_Arming::Method method)
// 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
@ -108,7 +107,6 @@ void Sub::init_disarm_motors()
}
}
// log disarm to the dataflash
Log_Write_Event(DATA_DISARMED);
// send disarm command to motors