Copter: add LOG_FROM_STARTUP definition
Uncommenting this line in APM_Config.h will start logging as soon as the board starts up instead of waiting for the vehicle to be armed
This commit is contained in:
parent
b2238b7c8a
commit
9bbf40109e
@ -44,6 +44,7 @@
|
||||
// other settings
|
||||
//#define THROTTLE_IN_DEADBAND 100 // redefine size of throttle deadband in pwm (0 ~ 1000)
|
||||
//#define LAND_REQUIRE_MIN_THROTTLE_TO_DISARM DISABLED // when set to DISABLED vehicle will disarm after landing (in LAND mode or RTL) even if pilot has not put throttle to zero
|
||||
//#define LOG_FROM_STARTUP // start logging as soon as the board starts up instead of waiting for the vehicle to be armed
|
||||
|
||||
//#define HIL_MODE HIL_MODE_SENSORS // build for hardware-in-the-loop simulation
|
||||
|
||||
|
@ -279,6 +279,10 @@ static void init_ardupilot()
|
||||
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
Log_Write_Startup();
|
||||
#ifdef LOG_FROM_STARTUP
|
||||
// start dataflash
|
||||
start_logging();
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// we don't want writes to the serial port to cause us to pause
|
||||
|
Loading…
Reference in New Issue
Block a user