mirror of https://github.com/ArduPilot/ardupilot
Copter: added LOG_BITMASK 1<<19 for logging raw accel/gyro data
useful for checking vibration handling
This commit is contained in:
parent
7d90033a36
commit
6dc3cff000
|
@ -1088,6 +1088,9 @@ static void one_hz_loop()
|
|||
|
||||
// update position controller alt limits
|
||||
update_poscon_alt_max();
|
||||
|
||||
// enable/disable raw gyro/accel logging
|
||||
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
|
||||
}
|
||||
|
||||
// called at 50hz
|
||||
|
|
|
@ -258,6 +258,7 @@ enum FlipState {
|
|||
#define MASK_LOG_WHEN_DISARMED (1UL<<16)
|
||||
#define MASK_LOG_MOTBATT (1UL<<17)
|
||||
#define MASK_LOG_IMU_FAST (1UL<<18)
|
||||
#define MASK_LOG_IMU_RAW (1UL<<19)
|
||||
#define MASK_LOG_ANY 0xFFFF
|
||||
|
||||
// DATA - event logging
|
||||
|
|
|
@ -261,6 +261,9 @@ static void init_ardupilot()
|
|||
// enable CPU failsafe
|
||||
failsafe_enable();
|
||||
|
||||
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
|
||||
ins.set_dataflash(&DataFlash);
|
||||
|
||||
cliSerial->print_P(PSTR("\nReady to FLY "));
|
||||
|
||||
// flag that initialisation has completed
|
||||
|
|
Loading…
Reference in New Issue