Copter: RCIN dataflash logging
This commit is contained in:
parent
84fdff4cd6
commit
af657d58b9
@ -890,7 +890,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
|
||||
{ update_copter_leds, 10, 55 },
|
||||
#endif
|
||||
{ update_mount, 2, 450 },
|
||||
{ ten_hz_logging_loop, 10, 260 },
|
||||
{ ten_hz_logging_loop, 10, 300 },
|
||||
{ fifty_hz_logging_loop, 2, 220 },
|
||||
{ perf_update, 1000, 200 },
|
||||
{ read_receiver_rssi, 10, 50 },
|
||||
@ -1150,6 +1150,9 @@ static void ten_hz_logging_loop()
|
||||
if (g.log_bitmask & MASK_LOG_ATTITUDE_MED) {
|
||||
Log_Write_Attitude();
|
||||
}
|
||||
if (g.log_bitmask & MASK_LOG_RCIN) {
|
||||
DataFlash.Log_Write_RCIN();
|
||||
}
|
||||
if (g.log_bitmask & MASK_LOG_MOTORS) {
|
||||
Log_Write_Motors();
|
||||
}
|
||||
|
@ -40,6 +40,7 @@ print_log_menu(void)
|
||||
if (g.log_bitmask & MASK_LOG_PM) cliSerial->printf_P(PSTR(" PM"));
|
||||
if (g.log_bitmask & MASK_LOG_CTUN) cliSerial->printf_P(PSTR(" CTUN"));
|
||||
if (g.log_bitmask & MASK_LOG_NTUN) cliSerial->printf_P(PSTR(" NTUN"));
|
||||
if (g.log_bitmask & MASK_LOG_RCIN) cliSerial->printf_P(PSTR(" RCIN"));
|
||||
if (g.log_bitmask & MASK_LOG_IMU) cliSerial->printf_P(PSTR(" IMU"));
|
||||
if (g.log_bitmask & MASK_LOG_CMD) cliSerial->printf_P(PSTR(" CMD"));
|
||||
if (g.log_bitmask & MASK_LOG_CURRENT) cliSerial->printf_P(PSTR(" CURRENT"));
|
||||
@ -131,7 +132,7 @@ select_logs(uint8_t argc, const Menu::arg *argv)
|
||||
TARG(PM);
|
||||
TARG(CTUN);
|
||||
TARG(NTUN);
|
||||
TARG(MODE);
|
||||
TARG(RCIN);
|
||||
TARG(IMU);
|
||||
TARG(CMD);
|
||||
TARG(CURRENT);
|
||||
|
@ -993,6 +993,9 @@
|
||||
#ifndef LOG_NTUN
|
||||
# define LOG_NTUN ENABLED
|
||||
#endif
|
||||
#ifndef LOG_RCIN
|
||||
# define LOG_RCIN ENABLED
|
||||
#endif
|
||||
#ifndef LOG_IMU
|
||||
# define LOG_IMU DISABLED
|
||||
#endif
|
||||
@ -1034,6 +1037,7 @@
|
||||
LOGBIT(PM) | \
|
||||
LOGBIT(CTUN) | \
|
||||
LOGBIT(NTUN) | \
|
||||
LOGBIT(RCIN) | \
|
||||
LOGBIT(IMU) | \
|
||||
LOGBIT(CMD) | \
|
||||
LOGBIT(CURRENT) | \
|
||||
|
@ -303,7 +303,7 @@ enum ap_message {
|
||||
#define MASK_LOG_PM (1<<3)
|
||||
#define MASK_LOG_CTUN (1<<4)
|
||||
#define MASK_LOG_NTUN (1<<5)
|
||||
#define MASK_LOG_MODE (1<<6) // not used
|
||||
#define MASK_LOG_RCIN (1<<6)
|
||||
#define MASK_LOG_IMU (1<<7)
|
||||
#define MASK_LOG_CMD (1<<8)
|
||||
#define MASK_LOG_CURRENT (1<<9)
|
||||
|
Loading…
Reference in New Issue
Block a user