DataFlash: fixed F4Light DataFlash logging

This commit is contained in:
night-ghost 2018-04-06 11:50:37 +05:00 committed by Andrew Tridgell
parent 79cd137625
commit 2a0f624d5a
2 changed files with 11 additions and 14 deletions

View File

@ -82,6 +82,7 @@ void DataFlash_Class::Init(const struct LogStructure *structures, uint8_t num_ty
_structures = structures;
#if defined(HAL_BOARD_LOG_DIRECTORY)
#if HAL_OS_POSIX_IO
if (_params.backend_types == DATAFLASH_BACKEND_FILE ||
_params.backend_types == DATAFLASH_BACKEND_BOTH) {
DFMessageWriter_DFLogStart *message_writer =
@ -97,7 +98,7 @@ void DataFlash_Class::Init(const struct LogStructure *structures, uint8_t num_ty
_next_backend++;
}
}
#elif CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT // restore dataflash logs
#elif CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
if (_params.backend_types == DATAFLASH_BACKEND_FILE ||
_params.backend_types == DATAFLASH_BACKEND_BOTH) {
@ -106,16 +107,21 @@ void DataFlash_Class::Init(const struct LogStructure *structures, uint8_t num_ty
new DFMessageWriter_DFLogStart(_firmware_string);
if (message_writer != nullptr) {
backends[_next_backend] = new DataFlash_Revo(*this, message_writer);
#if defined(BOARD_SDCARD_NAME) || defined(BOARD_DATAFLASH_FATFS)
backends[_next_backend] = new DataFlash_File(*this, message_writer, HAL_BOARD_LOG_DIRECTORY);
#else
backends[_next_backend] = new DataFlash_Revo(*this, message_writer); // restore dataflash logs
#endif
}
if (backends[_next_backend] == nullptr) {
hal.console->printf("Unable to open DataFlash_Revo");
printf("Unable to open DataFlash_Revo");
} else {
_next_backend++;
}
}
#endif
#endif
#endif // HAL_BOARD_LOG_DIRECTORY
#if DATAFLASH_MAVLINK_SUPPORT
if (_params.backend_types == DATAFLASH_BACKEND_MAVLINK ||

View File

@ -458,21 +458,12 @@ void DataFlash_Revo::ReadManufacturerID()
if (!cs_assert()) return;
// Read manufacturer and ID command...
#if 0
spi_write(JEDEC_DEVICE_ID); //
df_manufacturer = spi_read();
df_device = spi_read(); //memorytype
df_device = (df_device << 8) | spi_read(); //capacity
spi_read(); // ignore 4th byte
#else
cmd[0] = JEDEC_DEVICE_ID;
_spi->transfer(cmd, 1, buffer[1], 4);
df_manufacturer = buffer[1][0];
df_device = (buffer[1][1] << 8) | buffer[1][2]; //capacity
#endif
cs_release();
}
@ -1019,7 +1010,7 @@ void DataFlash_Revo::ListAvailableLogs(AP_HAL::BetterStream *port)
break;
}
}
port->println();
port->println("");
}
#endif