From 3eb28f16eaa5d4f4a085bcb87f334ba85d3ace84 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Wed, 28 Jan 2015 17:45:36 +1300 Subject: [PATCH 01/15] Basic read/write/erase flash functionality works from the CLI Very little code coverage tested yet, only writes of small sizes --- Makefile | 2 + src/main/drivers/bus_spi.c | 2 +- src/main/drivers/bus_spi.h | 2 +- src/main/drivers/flash.h | 31 +++ src/main/drivers/flash_m25p16.c | 278 +++++++++++++++++++ src/main/drivers/flash_m25p16.h | 39 +++ src/main/io/flashfs.c | 339 +++++++++++++++++++++++ src/main/io/flashfs.h | 45 +++ src/main/io/serial_cli.c | 84 ++++++ src/main/main.c | 8 + src/main/target/NAZE/hardware_revision.c | 4 +- src/main/target/NAZE/target.h | 9 + 12 files changed, 839 insertions(+), 4 deletions(-) create mode 100644 src/main/drivers/flash.h create mode 100644 src/main/drivers/flash_m25p16.c create mode 100644 src/main/drivers/flash_m25p16.h create mode 100644 src/main/io/flashfs.c create mode 100644 src/main/io/flashfs.h diff --git a/Makefile b/Makefile index f818e8107..7670f66fc 100644 --- a/Makefile +++ b/Makefile @@ -292,6 +292,8 @@ NAZE_SRC = startup_stm32f10x_md_gcc.S \ drivers/system_stm32f10x.c \ drivers/timer.c \ drivers/timer_stm32f10x.c \ + drivers/flash_m25p16.c \ + io/flashfs.c \ hardware_revision.c \ $(HIGHEND_SRC) \ $(COMMON_SRC) diff --git a/src/main/drivers/bus_spi.c b/src/main/drivers/bus_spi.c index 28fece232..248e17d39 100644 --- a/src/main/drivers/bus_spi.c +++ b/src/main/drivers/bus_spi.c @@ -198,7 +198,7 @@ uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t data) #endif } -bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, uint8_t *in, int len) +bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len) { uint16_t spiTimeout = 1000; diff --git a/src/main/drivers/bus_spi.h b/src/main/drivers/bus_spi.h index fd94abe09..62b20aeb0 100644 --- a/src/main/drivers/bus_spi.h +++ b/src/main/drivers/bus_spi.h @@ -24,7 +24,7 @@ bool spiInit(SPI_TypeDef *instance); void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor); uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t in); -bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, uint8_t *in, int len); +bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len); uint16_t spiGetErrorCounter(SPI_TypeDef *instance); void spiResetErrorCounter(SPI_TypeDef *instance); diff --git a/src/main/drivers/flash.h b/src/main/drivers/flash.h new file mode 100644 index 000000000..6ccba0d7b --- /dev/null +++ b/src/main/drivers/flash.h @@ -0,0 +1,31 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#include + +typedef struct flashGeometry_t { + uint8_t sectors; + + uint16_t pagesPerSector; + uint16_t pageSize; + + uint32_t sectorSize; + + uint32_t totalSize; +} flashGeometry_t; diff --git a/src/main/drivers/flash_m25p16.c b/src/main/drivers/flash_m25p16.c new file mode 100644 index 000000000..864eacd77 --- /dev/null +++ b/src/main/drivers/flash_m25p16.c @@ -0,0 +1,278 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include +#include +#include + +#include "platform.h" + +#include "drivers/flash_m25p16.h" +#include "drivers/bus_spi.h" +#include "drivers/system.h" + +#define M25P16_INSTRUCTION_RDID 0x9F +#define M25P16_INSTRUCTION_READ_BYTES 0x03 +#define M25P16_INSTRUCTION_READ_STATUS_REG 0x05 +#define M25P16_INSTRUCTION_WRITE_STATUS_REG 0x01 +#define M25P16_INSTRUCTION_WRITE_ENABLE 0x06 +#define M25P16_INSTRUCTION_WRITE_DISABLE 0x04 +#define M25P16_INSTRUCTION_PAGE_PROGRAM 0x02 +#define M25P16_INSTRUCTION_SECTOR_ERASE 0xD8 +#define M25P16_INSTRUCTION_BULK_ERASE 0xC7 + +#define M25P16_STATUS_FLAG_WRITE_IN_PROGRESS 0x01 +#define M25P16_STATUS_FLAG_WRITE_ENABLED 0x02 + +#define DISABLE_M25P16 GPIO_SetBits(M25P16_CS_GPIO, M25P16_CS_PIN) +#define ENABLE_M25P16 GPIO_ResetBits(M25P16_CS_GPIO, M25P16_CS_PIN) + +// The timeout we expect between being able to issue page program instructions +#define DEFAULT_TIMEOUT_MILLIS 6 + +// These take sooooo long: +#define SECTOR_ERASE_TIMEOUT_MILLIS 5000 +#define BULK_ERASE_TIMEOUT_MILLIS 21000 + +static flashGeometry_t geometry; + +/* + * Whether we've performed an action that could have made the device busy for writes. + * + * This allows us to avoid polling for writable status when it is definitely ready already. + */ +static bool couldBeBusy = false; + +/** + * Send the given command byte to the device. + */ +static void m25p16_performOneByteCommand(uint8_t command) +{ + ENABLE_M25P16; + + spiTransferByte(M25P16_SPI_INSTANCE, command); + + DISABLE_M25P16; +} + +/** + * The flash requires this write enable command to be sent before commands that would cause + * a write like program and erase. + */ +static void m25p16_writeEnable() +{ + m25p16_performOneByteCommand(M25P16_INSTRUCTION_WRITE_ENABLE); + + // Assume that we're about to do some writing, so the device is just about to become busy + couldBeBusy = true; +} + +static uint8_t m25p16_readStatus() +{ + uint8_t command[2] = {M25P16_INSTRUCTION_READ_STATUS_REG, 0}; + uint8_t in[2]; + + ENABLE_M25P16; + + spiTransfer(M25P16_SPI_INSTANCE, in, command, sizeof(command)); + + DISABLE_M25P16; + + return in[1]; +} + +bool m25p16_isReady() +{ + couldBeBusy = couldBeBusy && ((m25p16_readStatus() & M25P16_STATUS_FLAG_WRITE_IN_PROGRESS) != 0); + + return !couldBeBusy; +} + +bool m25p16_waitForReady(uint32_t timeoutMillis) +{ + uint32_t time = millis(); + while (!m25p16_isReady()) { + if (millis() - time > timeoutMillis) { + return false; + } + } + + return true; +} + +/** + * Read chip identification and geometry information (into global `geometry`). + * + * Returns true if we get valid ident, false if something bad happened like there is no M25P16. + */ +static bool m25p16_readIdentification() +{ + uint8_t out[] = { M25P16_INSTRUCTION_RDID, 0, 0, 0}; + uint8_t in[4]; + + delay(50); // short delay required after initialisation of SPI device instance. + + in[1] = 0; // Just in case transfer fails and writes nothing + + ENABLE_M25P16; + + spiTransfer(M25P16_SPI_INSTANCE, in, out, sizeof(out)); + + // Clearing the CS bit terminates the command early so we don't have to read the chip UID: + DISABLE_M25P16; + + // Check manufacturer, memory type, and capacity + if (in[1] == 0x20 && in[2] == 0x20 && in[3] == 0x15) { + // In the future we can support other chip geometries here: + geometry.sectors = 32; + geometry.pagesPerSector = 256; + geometry.pageSize = 256; + + geometry.sectorSize = geometry.pagesPerSector * geometry.pageSize; + geometry.totalSize = geometry.sectorSize * geometry.sectors; + + couldBeBusy = true; // Just for luck we'll assume the chip could be busy even though it isn't specced to be + + return true; + } + + geometry.sectors = 0; + geometry.pagesPerSector = 0; + geometry.pageSize = 0; + + geometry.sectorSize = 0; + geometry.totalSize = 0; + + return false; +} + +/** + * Initialize the driver, must be called before any other routines. + * + * Attempts to detect a connected m25p16. If found, true is returned and device capacity can be fetched with + * m25p16_getGeometry(). + */ +bool m25p16_init() +{ + //Maximum speed for standard READ command is 20mHz, other commands tolerate 25mHz + spiSetDivisor(M25P16_SPI_INSTANCE, SPI_18MHZ_CLOCK_DIVIDER); + + return m25p16_readIdentification(); +} + +/** + * Erase a sector full of bytes to all 1's at the given byte offset in the flash chip. + */ +void m25p16_eraseSector(uint32_t address) +{ + uint8_t out[] = { M25P16_INSTRUCTION_SECTOR_ERASE, (address >> 16) & 0xFF, (address >> 8) & 0xFF, address & 0xFF}; + + m25p16_waitForReady(SECTOR_ERASE_TIMEOUT_MILLIS); + + m25p16_writeEnable(); + + ENABLE_M25P16; + + spiTransfer(M25P16_SPI_INSTANCE, NULL, out, sizeof(out)); + + DISABLE_M25P16; +} + +void m25p16_eraseCompletely() +{ + m25p16_waitForReady(BULK_ERASE_TIMEOUT_MILLIS); + + m25p16_writeEnable(); + + m25p16_performOneByteCommand(M25P16_INSTRUCTION_BULK_ERASE); +} + +void m25p16_pageProgramBegin(uint32_t address) +{ + uint8_t command[] = { M25P16_INSTRUCTION_PAGE_PROGRAM, (address >> 16) & 0xFF, (address >> 8) & 0xFF, address & 0xFF}; + + m25p16_waitForReady(DEFAULT_TIMEOUT_MILLIS); + + m25p16_writeEnable(); + + ENABLE_M25P16; + + spiTransfer(M25P16_SPI_INSTANCE, NULL, command, sizeof(command)); +} + +void m25p16_pageProgramContinue(const uint8_t *data, int length) +{ + spiTransfer(M25P16_SPI_INSTANCE, NULL, data, length); +} + +void m25p16_pageProgramFinish() +{ + DISABLE_M25P16; +} + +/** + * Write bytes to a flash page. Address must not cross a page boundary. + * + * Bits can only be set to zero, not from zero back to one again. In order to set bits to 1, use the erase command. + * + * Length must be smaller than the page size. + * + * This will wait for the flash to become ready before writing begins. + * + * Datasheet indicates typical programming time is 0.8ms for 256 bytes, 0.2ms for 64 bytes, 0.05ms for 16 bytes. + * (Although the maximum possible write time is noted as 5ms). + * + * If you want to write multiple buffers (whose sum of sizes is still not more than the page size) then you can + * break this operation up into one beginProgram call, one or more continueProgram calls, and one finishProgram call. + */ +void m25p16_pageProgram(uint32_t address, const uint8_t *data, int length) +{ + m25p16_pageProgramBegin(address); + + m25p16_pageProgramContinue(data, length); + + m25p16_pageProgramFinish(); +} + +/** + * Read `length` bytes into the provided `buffer` from the flash starting from the given `address` (which need not lie + * on a page boundary). + * + * The number of bytes actually read is returned, which can be zero if an error occurred. + */ +int m25p16_readBytes(uint32_t address, uint8_t *buffer, int length) +{ + uint8_t command[] = { M25P16_INSTRUCTION_READ_BYTES, (address >> 16) & 0xFF, (address >> 8) & 0xFF, address & 0xFF}; + + if (!m25p16_waitForReady(DEFAULT_TIMEOUT_MILLIS)) { + return 0; + } + + ENABLE_M25P16; + + spiTransfer(M25P16_SPI_INSTANCE, NULL, command, sizeof(command)); + spiTransfer(M25P16_SPI_INSTANCE, buffer, NULL, length); + + DISABLE_M25P16; + + return length; +} + +const flashGeometry_t* m25p16_getGeometry() +{ + return &geometry; +} diff --git a/src/main/drivers/flash_m25p16.h b/src/main/drivers/flash_m25p16.h new file mode 100644 index 000000000..79d782715 --- /dev/null +++ b/src/main/drivers/flash_m25p16.h @@ -0,0 +1,39 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#include +#include "flash.h" + +bool m25p16_init(); + +void m25p16_eraseSector(uint32_t address); +void m25p16_eraseCompletely(); + +void m25p16_pageProgram(uint32_t address, const uint8_t *data, int length); + +void m25p16_pageProgramBegin(uint32_t address); +void m25p16_pageProgramContinue(const uint8_t *data, int length); +void m25p16_pageProgramFinish(); + +int m25p16_readBytes(uint32_t address, uint8_t *buffer, int length); + +bool m25p16_isReady(); +bool m25p16_waitForReady(uint32_t timeoutMillis); + +const flashGeometry_t* m25p16_getGeometry(); diff --git a/src/main/io/flashfs.c b/src/main/io/flashfs.c new file mode 100644 index 000000000..3a6795ff1 --- /dev/null +++ b/src/main/io/flashfs.c @@ -0,0 +1,339 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +/** + * This provides a stream interface to a flash chip if one is present. + * + * Note that bits can only be set to 0 when writing, not back to 1 from 0. You must erase sectors in order + * to bring bits back to 1 again. + */ + +#include +#include + +#include "drivers/flash_m25p16.h" +#include "flashfs.h" + +static uint8_t flashWriteBuffer[FLASHFS_WRITE_BUFFER_SIZE]; + +/* The position of our head and tail in the circular flash write buffer. + * + * The head is the index that a byte would be inserted into on writing, while the tail is the index of the + * oldest byte that has yet to be written to flash. + * + * When the circular buffer is empty, head == tail + */ +static uint8_t bufferHead = 0, bufferTail = 0; + +// The position of our tail in the overall flash address space: +static uint32_t tailAddress = 0; +// The index of the tail within the flash page it is inside +static uint16_t tailIndexInPage = 0; + +static bool shouldFlush = false; + +static void flashfsClearBuffer() +{ + bufferTail = bufferHead = 0; + shouldFlush = false; +} + +static void flashfsSetTailAddress(uint32_t address) +{ + tailAddress = address; + tailIndexInPage = tailAddress % m25p16_getGeometry()->pageSize; +} + +void flashfsEraseCompletely() +{ + m25p16_eraseCompletely(); + + flashfsClearBuffer(); + + flashfsSetTailAddress(0); +} + +/** + * Start and end must lie on sector boundaries, or they will be rounded out to sector boundaries such that + * all the bytes in the range [start...end) are erased. + */ +void flashfsEraseRange(uint32_t start, uint32_t end) +{ + const flashGeometry_t *geometry = m25p16_getGeometry(); + + if (geometry->sectorSize <= 0) + return; + + // Round the start down to a sector boundary + int startSector = start / geometry->sectorSize; + + // And the end upward + int endSector = end / geometry->sectorSize; + int endRemainder = end % geometry->sectorSize; + + if (endRemainder > 0) { + endSector++; + } + + for (int i = startSector; i < endSector; i++) { + m25p16_eraseSector(i * geometry->sectorSize); + } +} + +uint32_t flashfsGetSize() +{ + return m25p16_getGeometry()->totalSize; +} + +const flashGeometry_t* flashfsGetGeometry() +{ + return m25p16_getGeometry(); +} + +static uint32_t flashfsTransmitBufferUsed() +{ + if (bufferHead >= bufferTail) + return bufferHead - bufferTail; + + return FLASHFS_WRITE_BUFFER_SIZE - bufferTail + bufferHead; +} + +static uint32_t flashfsTransmitBufferRemaining() +{ + /* + * We subtract one from the actual transmit buffer remaining space to allow us to distinguish + * between completely full and completely empty states, that would otherwise both have head = tail + */ + return FLASHFS_WRITE_BUFFER_USABLE - flashfsTransmitBufferUsed(); +} + +/** + * Waits for the flash device to be ready to accept writes, then write the given buffers to flash. + * + * Advances the address of the beginning of the supplied buffers and reduces the size of the buffers according to how + * many bytes get written. + * + * bufferCount: the number of buffers provided + * buffers: an array of pointers to the beginning of buffers + * bufferSizes: an array of the sizes of those buffers + */ +static void flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSizes, int bufferCount) +{ + const flashGeometry_t *geometry = m25p16_getGeometry(); + + uint32_t bytesTotalToWrite = 0; + uint32_t bytesTotalRemaining; + + int i; + + for (i = 0; i < bufferCount; i++) { + bytesTotalToWrite += bufferSizes[i]; + } + + bytesTotalRemaining = bytesTotalToWrite; + + while (bytesTotalRemaining > 0) { + uint32_t bytesTotalThisIteration; + uint32_t bytesRemainThisIteration; + + // If we would cross a page boundary, only write up to the boundary in this iteration: + if (tailIndexInPage + bytesTotalRemaining > geometry->pageSize) { + bytesTotalThisIteration = geometry->pageSize - tailIndexInPage; + } else { + bytesTotalThisIteration = bytesTotalRemaining; + } + + m25p16_pageProgramBegin(tailAddress); + + bytesRemainThisIteration = bytesTotalThisIteration; + + for (i = 0; i < bufferCount; i++) { + if (bufferSizes[i] > 0) { + // Is buffer larger than our write limit? Write our limit out of it + if (bufferSizes[i] >= bytesRemainThisIteration) { + m25p16_pageProgramContinue(buffers[i], bytesRemainThisIteration); + + buffers[i] += bytesRemainThisIteration; + bufferSizes[i] -= bytesRemainThisIteration; + + bytesRemainThisIteration = 0; + break; + } else { + // We'll still have more to write after finishing this buffer off + m25p16_pageProgramContinue(buffers[i], bufferSizes[i]); + + bytesRemainThisIteration -= bufferSizes[i]; + + buffers[i] += bufferSizes[i]; + bufferSizes[i] = 0; + } + } + } + + m25p16_pageProgramFinish(); + + bytesTotalRemaining -= bytesTotalThisIteration; + + // Advance the cursor in the file system to match the bytes we wrote + flashfsSetTailAddress(tailAddress + bytesTotalToWrite); + } +} + +/* + * Since the buffered data might wrap around the end of the circular buffer, we can have two segments of data to write, + * an initial portion and a possible wrapped portion. + * + * This routine will fill the details of those buffers into the provided arrays, which must be at least 2 elements long. + */ +static void flashfsGetDirtyDataBuffers(uint8_t const *buffers[], uint32_t bufferSizes[]) +{ + buffers[0] = flashWriteBuffer + bufferTail; + buffers[1] = flashWriteBuffer + 0; + + if (bufferHead >= bufferTail) { + bufferSizes[0] = bufferHead - bufferTail; + bufferSizes[1] = 0; + } else { + bufferSizes[0] = FLASHFS_WRITE_BUFFER_SIZE - bufferTail; + bufferSizes[1] = bufferHead; + } +} + +/** + * If the flash is ready to accept writes, flush the buffer to it, otherwise schedule + * a flush for later and return immediately. + */ +void flashfsFlushAsync() +{ + if (bufferHead == bufferTail) { + return; // Nothing to flush + } + + if (m25p16_isReady()) { + uint8_t const * buffers[2]; + uint32_t bufferSizes[2]; + + flashfsGetDirtyDataBuffers(buffers, bufferSizes); + flashfsWriteBuffers(buffers, bufferSizes, 2); + + flashfsClearBuffer(); + } else { + shouldFlush = true; + } +} + +/** + * Wait for the flash to become ready and begin flushing any buffered data to flash. + * + * The flash will still be busy some time after this sync completes, but space will + * be freed up to accept more writes in the write buffer. + */ +void flashfsFlushSync() +{ + if (bufferHead == bufferTail) + return; // Nothing to write + + m25p16_waitForReady(10); //TODO caller should customize timeout + + flashfsFlushAsync(); +} + +void flashfsSeekAbs(uint32_t offset) +{ + flashfsFlushSync(); + + flashfsSetTailAddress(offset); +} + +void flashfsSeekRel(int32_t offset) +{ + flashfsFlushSync(); + + flashfsSetTailAddress(tailAddress + offset); +} + +void flashfsWriteByte(uint8_t byte) +{ + flashWriteBuffer[bufferHead++] = byte; + + if (bufferHead >= FLASHFS_WRITE_BUFFER_SIZE) { + bufferHead = 0; + } + + if (flashfsTransmitBufferUsed() >= FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN) { + flashfsFlushAsync(); + } +} + +void flashfsWrite(const uint8_t *data, unsigned int len) +{ + // Would writing this cause our buffer to reach the flush threshold? If so just write it now + if (len + flashfsTransmitBufferUsed() >= FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN || shouldFlush) { + uint8_t const * buffers[3]; + uint32_t bufferSizes[3]; + + // There could be two dirty buffers to write out already: + flashfsGetDirtyDataBuffers(buffers, bufferSizes); + + // Plus the buffer the user supplied: + buffers[2] = data; + bufferSizes[2] = len; + + // Write all three buffers through to the flash + flashfsWriteBuffers(buffers, bufferSizes, 3); + + // And now our buffer is empty + flashfsClearBuffer(); + } + + // Buffer up the data the user supplied instead of writing it right away + + // First write the portion before we wrap around the end of the circular buffer + unsigned int bufferBytesBeforeLoop = FLASHFS_WRITE_BUFFER_SIZE - bufferHead; + + unsigned int firstPortion = len < bufferBytesBeforeLoop ? len : bufferBytesBeforeLoop; + unsigned int remainder = firstPortion < len ? len - firstPortion : 0; + + for (unsigned int i = 0; i < firstPortion; i++) { + flashWriteBuffer[bufferHead++] = *data; + data++; + } + + if (bufferHead == FLASHFS_WRITE_BUFFER_SIZE) { + bufferHead = 0; + } + + // Then the remainder (if any) + for (unsigned int i = 0; i < remainder; i++) { + flashWriteBuffer[bufferHead++] = *data; + data++; + } +} + +/** + * Read `len` bytes from the current cursor location into the supplied buffer. + * + * Returns the number of bytes actually read which may be less than that requested. + */ +int flashfsRead(uint8_t *data, unsigned int len) +{ + int result = m25p16_readBytes(tailAddress, data, len); + + flashfsSetTailAddress(tailAddress + result); + + return result; +} diff --git a/src/main/io/flashfs.h b/src/main/io/flashfs.h new file mode 100644 index 000000000..a9f8403da --- /dev/null +++ b/src/main/io/flashfs.h @@ -0,0 +1,45 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#include + +#include "drivers/flash.h" + +#define FLASHFS_WRITE_BUFFER_SIZE 128 +#define FLASHFS_WRITE_BUFFER_USABLE (FLASHFS_WRITE_BUFFER_SIZE - 1) + +// Automatically trigger a flush when this much data is in the buffer +#define FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN 64 + +void flashfsEraseCompletely(); +void flashfsEraseRange(uint32_t start, uint32_t end); + +uint32_t flashfsGetSize(); +const flashGeometry_t* flashfsGetGeometry(); + +void flashfsSeekAbs(uint32_t offset); +void flashfsSeekRel(int32_t offset); + +void flashfsWriteByte(uint8_t byte); +void flashfsWrite(const uint8_t *data, unsigned int len); + +int flashfsRead(uint8_t *data, unsigned int len); + +void flashfsFlushAsync(); +void flashfsFlushSync(); diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index adf96d7f5..66aaf3464 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -44,6 +44,7 @@ #include "drivers/gpio.h" #include "drivers/timer.h" #include "drivers/pwm_rx.h" +#include "drivers/flash_m25p16.h" #include "flight/flight.h" #include "flight/mixer.h" #include "flight/navigation.h" @@ -55,6 +56,7 @@ #include "io/rc_controls.h" #include "io/serial.h" #include "io/ledstrip.h" +#include "io/flashfs.h" #include "rx/spektrum.h" #include "sensors/battery.h" #include "sensors/boardalignment.h" @@ -111,6 +113,13 @@ static void cliColor(char *cmdline); static void cliMixer(char *cmdline); #endif +#ifdef FLASHFS +static void cliFlashIdent(char *cmdline); +static void cliFlashEraseSector(char *cmdline); +static void cliFlashWrite(char *cmdline); +static void cliFlashRead(char *cmdline); +#endif + // signal that we're in cli mode uint8_t cliMode = 0; @@ -166,6 +175,12 @@ const clicmd_t cmdTable[] = { { "dump", "print configurable settings in a pastable form", cliDump }, { "exit", "", cliExit }, { "feature", "list or -val or val", cliFeature }, +#ifdef FLASHFS + { "flash_erase_sector", "erase flash sector at the given address", cliFlashEraseSector }, + { "flash_ident", "get flash chip details", cliFlashIdent }, + { "flash_read", "read text from the given address", cliFlashRead }, + { "flash_write", "write text to the given address", cliFlashWrite }, +#endif { "get", "get variable value", cliGet }, #ifdef GPS { "gpspassthrough", "passthrough gps to serial", cliGpsPassthrough }, @@ -729,6 +744,75 @@ static void cliColor(char *cmdline) } #endif +#ifdef FLASHFS + +static void cliFlashIdent(char *cmdline) +{ + const flashGeometry_t *layout = flashfsGetGeometry(); + + UNUSED(cmdline); + + printf("Flash sectors=%u, sectorSize=%u, pagesPerSector=%u, pageSize=%u, totalSize=%u\r\n", + layout->sectors, layout->sectorSize, layout->pagesPerSector, layout->pageSize, layout->totalSize); +} + +static void cliFlashEraseSector(char *cmdline) +{ + uint32_t address = atoi(cmdline); + + flashfsEraseRange(address, address + 1); + printf("Erased sector at %u.\r\n", address); +} + +static void cliFlashWrite(char *cmdline) +{ + uint32_t address = atoi(cmdline); + char *text = strchr(cmdline, ' '); + + if (!text) { + printf("Missing text to write.\r\n"); + } else { + flashfsSeekAbs(address); + flashfsWrite((uint8_t*)text, strlen(text)); + flashfsFlushSync(); + + printf("Wrote %u bytes at %u.\r\n", strlen(text), address); + } +} + +static void cliFlashRead(char *cmdline) +{ + uint32_t address = atoi(cmdline); + uint32_t length; + uint32_t i; + + uint8_t buffer[32]; + + char *nextArg = strchr(cmdline, ' '); + + if (!nextArg) { + printf("Missing length argument.\r\n"); + } else { + length = atoi(nextArg); + if (length > 32) { + length = 32; + printf("Length truncated to 32 bytes.\r\n"); + } + + flashfsSeekAbs(address); + flashfsRead(buffer, length); + + printf("Read %u bytes at %u:\r\n", length, address); + + for (i = 0; i < length; i++) { + printf("%c", (char) buffer[i]); + } + printf("\r\n"); + } +} + +#endif + static void dumpValues(uint16_t mask) { uint32_t i; diff --git a/src/main/main.c b/src/main/main.c index 08c1e6469..a4fcfccb2 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -44,6 +44,7 @@ #include "drivers/bus_i2c.h" #include "drivers/bus_spi.h" #include "drivers/inverter.h" +#include "drivers/flash_m25p16.h" #include "flight/flight.h" #include "flight/mixer.h" @@ -348,6 +349,13 @@ void init(void) initTelemetry(); #endif +#ifdef FLASHFS + #ifdef NAZE + // naze32 rev5 and above have 16mbit of flash available + m25p16_init(); + #endif +#endif + #ifdef BLACKBOX initBlackbox(); #endif diff --git a/src/main/target/NAZE/hardware_revision.c b/src/main/target/NAZE/hardware_revision.c index 3726c79e4..bed18b72f 100644 --- a/src/main/target/NAZE/hardware_revision.c +++ b/src/main/target/NAZE/hardware_revision.c @@ -58,7 +58,7 @@ void detectHardwareRevision(void) #define SPI_DEVICE_MPU (2) #define M25P16_INSTRUCTION_RDID 0x9F -#define FLASH_M25P16 (0x202015) +#define FLASH_M25P16_ID (0x202015) uint8_t detectSpiDevice(void) { @@ -74,7 +74,7 @@ uint8_t detectSpiDevice(void) DISABLE_SPI_CS; flash_id = in[1] << 16 | in[2] << 8 | in[3]; - if (flash_id == FLASH_M25P16) + if (flash_id == FLASH_M25P16_ID) return SPI_DEVICE_FLASH; // try autodetect MPU diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h index ffd179baa..217d14366 100644 --- a/src/main/target/NAZE/target.h +++ b/src/main/target/NAZE/target.h @@ -56,10 +56,19 @@ #define NAZE_SPI_CS_GPIO GPIOB #define NAZE_SPI_CS_PIN GPIO_Pin_12 +// We either have this 16mbit flash chip on SPI or the MPU6500 acc/gyro depending on board revision: +#define M25P16_CS_GPIO NAZE_SPI_CS_GPIO +#define M25P16_CS_PIN NAZE_SPI_CS_PIN +#define M25P16_SPI_INSTANCE NAZE_SPI_INSTANCE + #define MPU6500_CS_GPIO NAZE_SPI_CS_GPIO #define MPU6500_CS_PIN NAZE_SPI_CS_PIN #define MPU6500_SPI_INSTANCE NAZE_SPI_INSTANCE +#define FLASHFS + +#define USE_FLASH_M25P16 + #define GYRO #define USE_GYRO_MPU3050 #define USE_GYRO_MPU6050 From 2e14faeef6caf05fd8de603d4fbb45e765b31e6a Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Wed, 28 Jan 2015 20:48:06 +1300 Subject: [PATCH 02/15] Comment updates, allow CLI flash read to read more in one operation --- src/main/drivers/flash_m25p16.c | 6 +++++- src/main/io/flashfs.c | 11 +++++------ src/main/io/serial_cli.c | 20 +++++++++++--------- 3 files changed, 21 insertions(+), 16 deletions(-) diff --git a/src/main/drivers/flash_m25p16.c b/src/main/drivers/flash_m25p16.c index 864eacd77..3eac01041 100644 --- a/src/main/drivers/flash_m25p16.c +++ b/src/main/drivers/flash_m25p16.c @@ -97,6 +97,7 @@ static uint8_t m25p16_readStatus() bool m25p16_isReady() { + // If couldBeBusy is false, don't bother to poll the flash chip for its status couldBeBusy = couldBeBusy && ((m25p16_readStatus() & M25P16_STATUS_FLAG_WRITE_IN_PROGRESS) != 0); return !couldBeBusy; @@ -126,7 +127,10 @@ static bool m25p16_readIdentification() delay(50); // short delay required after initialisation of SPI device instance. - in[1] = 0; // Just in case transfer fails and writes nothing + /* Just in case transfer fails and writes nothing, so we don't try to verify the ID against random garbage + * from the stack: + */ + in[1] = 0; ENABLE_M25P16; diff --git a/src/main/io/flashfs.c b/src/main/io/flashfs.c index 3a6795ff1..015738eb3 100644 --- a/src/main/io/flashfs.c +++ b/src/main/io/flashfs.c @@ -114,15 +114,11 @@ static uint32_t flashfsTransmitBufferUsed() static uint32_t flashfsTransmitBufferRemaining() { - /* - * We subtract one from the actual transmit buffer remaining space to allow us to distinguish - * between completely full and completely empty states, that would otherwise both have head = tail - */ return FLASHFS_WRITE_BUFFER_USABLE - flashfsTransmitBufferUsed(); } /** - * Waits for the flash device to be ready to accept writes, then write the given buffers to flash. + * Waits for the flash device to be ready to accept writes, then write the given buffers to flash sequentially. * * Advances the address of the beginning of the supplied buffers and reduces the size of the buffers according to how * many bytes get written. @@ -150,7 +146,10 @@ static void flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSizes, uint32_t bytesTotalThisIteration; uint32_t bytesRemainThisIteration; - // If we would cross a page boundary, only write up to the boundary in this iteration: + /* + * Each page needs to be saved in a separate program operation, so + * if we would cross a page boundary, only write up to the boundary in this iteration: + */ if (tailIndexInPage + bytesTotalRemaining > geometry->pageSize) { bytesTotalThisIteration = geometry->pageSize - tailIndexInPage; } else { diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 66aaf3464..c4e010cc5 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -44,7 +44,6 @@ #include "drivers/gpio.h" #include "drivers/timer.h" #include "drivers/pwm_rx.h" -#include "drivers/flash_m25p16.h" #include "flight/flight.h" #include "flight/mixer.h" #include "flight/navigation.h" @@ -794,18 +793,21 @@ static void cliFlashRead(char *cmdline) printf("Missing length argument.\r\n"); } else { length = atoi(nextArg); - if (length > 32) { - length = 32; - printf("Length truncated to 32 bytes.\r\n"); - } + + printf("Reading %u bytes at %u:\r\n", length, address); flashfsSeekAbs(address); - flashfsRead(buffer, length); - printf("Read %u bytes at %u:\r\n", length, address); + while (length > 0) { + int bytesToRead = length < 32 ? length : 32; - for (i = 0; i < length; i++) { - printf("%c", (char) buffer[i]); + flashfsRead(buffer, bytesToRead); + + for (i = 0; i < bytesToRead; i++) { + printf("%c", (char) buffer[i]); + } + + length -= bytesToRead; } printf("\r\n"); } From 5a57dda66587821dbef0ae1c1ba74bef15aab2c7 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Wed, 28 Jan 2015 22:14:49 +1300 Subject: [PATCH 03/15] Adding blackbox device setting and basic flashfs support for it --- src/main/blackbox/blackbox.c | 4 ++ src/main/blackbox/blackbox_io.c | 116 +++++++++++++++++++++++--------- src/main/blackbox/blackbox_io.h | 3 + src/main/config/config.c | 1 + src/main/config/config_master.h | 1 + src/main/io/flashfs.c | 22 +++--- src/main/io/serial_cli.c | 3 +- 7 files changed, 110 insertions(+), 40 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 2440af0a5..de439bed1 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -605,6 +605,10 @@ static void validateBlackboxConfig() masterConfig.blackbox_rate_num /= div; masterConfig.blackbox_rate_denom /= div; } + + if (!(masterConfig.blackbox_device == BLACKBOX_DEVICE_SERIAL || masterConfig.blackbox_device == BLACKBOX_DEVICE_FLASH)) { + masterConfig.blackbox_device = BLACKBOX_DEVICE_SERIAL; + } } void startBlackbox(void) diff --git a/src/main/blackbox/blackbox_io.c b/src/main/blackbox/blackbox_io.c index 194c03c40..35fe44eec 100644 --- a/src/main/blackbox/blackbox_io.c +++ b/src/main/blackbox/blackbox_io.c @@ -55,6 +55,8 @@ #include "config/config_profile.h" #include "config/config_master.h" +#include "io/flashfs.h" + #define BLACKBOX_BAUDRATE 115200 #define BLACKBOX_INITIAL_PORT_MODE MODE_TX @@ -67,7 +69,17 @@ static uint32_t previousBaudRate; void blackboxWrite(uint8_t value) { - serialWrite(blackboxPort, value); + switch (masterConfig.blackbox_device) { +#ifdef FLASHFS + case BLACKBOX_DEVICE_FLASH: + flashfsWriteByte(value); + break; +#endif + case BLACKBOX_DEVICE_SERIAL: + default: + serialWrite(blackboxPort, value); + break; + } } static void _putc(void *p, char c) @@ -378,7 +390,16 @@ void blackboxWriteTag8_8SVB(int32_t *values, int valueCount) */ void blackboxDeviceFlush(void) { - //Presently a no-op on serial + switch (masterConfig.blackbox_device) { + case BLACKBOX_DEVICE_SERIAL: + //Presently a no-op on serial, as serial is continuously being drained out of its buffer + break; +#ifdef FLASHFS + case BLACKBOX_DEVICE_FLASH: + flashfsFlushSync(); + break; +#endif + } } /** @@ -386,23 +407,6 @@ void blackboxDeviceFlush(void) */ bool blackboxDeviceOpen(void) { - blackboxPort = findOpenSerialPort(FUNCTION_BLACKBOX); - if (blackboxPort) { - previousPortMode = blackboxPort->mode; - previousBaudRate = blackboxPort->baudRate; - - serialSetBaudRate(blackboxPort, BLACKBOX_BAUDRATE); - serialSetMode(blackboxPort, BLACKBOX_INITIAL_PORT_MODE); - beginSerialPortFunction(blackboxPort, FUNCTION_BLACKBOX); - } else { - blackboxPort = openSerialPort(FUNCTION_BLACKBOX, NULL, BLACKBOX_BAUDRATE, BLACKBOX_INITIAL_PORT_MODE, SERIAL_NOT_INVERTED); - - if (blackboxPort) { - previousPortMode = blackboxPort->mode; - previousBaudRate = blackboxPort->baudRate; - } - } - /* * We want to write at about 7200 bytes per second to give the OpenLog a good chance to save to disk. If * about looptime microseconds elapse between our writes, this is the budget of how many bytes we should @@ -412,26 +416,78 @@ bool blackboxDeviceOpen(void) */ blackboxWriteChunkSize = MAX((masterConfig.looptime * 9) / 1250, 4); - return blackboxPort != NULL; + switch (masterConfig.blackbox_device) { + case BLACKBOX_DEVICE_SERIAL: + blackboxPort = findOpenSerialPort(FUNCTION_BLACKBOX); + if (blackboxPort) { + previousPortMode = blackboxPort->mode; + previousBaudRate = blackboxPort->baudRate; + + serialSetBaudRate(blackboxPort, BLACKBOX_BAUDRATE); + serialSetMode(blackboxPort, BLACKBOX_INITIAL_PORT_MODE); + beginSerialPortFunction(blackboxPort, FUNCTION_BLACKBOX); + } else { + blackboxPort = openSerialPort(FUNCTION_BLACKBOX, NULL, BLACKBOX_BAUDRATE, BLACKBOX_INITIAL_PORT_MODE, SERIAL_NOT_INVERTED); + + if (blackboxPort) { + previousPortMode = blackboxPort->mode; + previousBaudRate = blackboxPort->baudRate; + } + } + + return blackboxPort != NULL; + break; +#ifdef FLASHFS + case BLACKBOX_DEVICE_FLASH: + if (flashfsGetSize() == 0) + return false; + + return true; + break; +#endif + default: + return false; + } } void blackboxDeviceClose(void) { - serialSetMode(blackboxPort, previousPortMode); - serialSetBaudRate(blackboxPort, previousBaudRate); + switch (masterConfig.blackbox_device) { + case BLACKBOX_DEVICE_SERIAL: + serialSetMode(blackboxPort, previousPortMode); + serialSetBaudRate(blackboxPort, previousBaudRate); - endSerialPortFunction(blackboxPort, FUNCTION_BLACKBOX); + endSerialPortFunction(blackboxPort, FUNCTION_BLACKBOX); - /* - * Normally this would be handled by mw.c, but since we take an unknown amount - * of time to shut down asynchronously, we're the only ones that know when to call it. - */ - if (isSerialPortFunctionShared(FUNCTION_BLACKBOX, FUNCTION_MSP)) { - mspAllocateSerialPorts(&masterConfig.serialConfig); + /* + * Normally this would be handled by mw.c, but since we take an unknown amount + * of time to shut down asynchronously, we're the only ones that know when to call it. + */ + if (isSerialPortFunctionShared(FUNCTION_BLACKBOX, FUNCTION_MSP)) { + mspAllocateSerialPorts(&masterConfig.serialConfig); + } + break; +#ifdef FLASHFS + case BLACKBOX_DEVICE_FLASH: + flashfsFlushSync(); + break; +#endif } } bool isBlackboxDeviceIdle(void) { - return isSerialTransmitBufferEmpty(blackboxPort); + switch (masterConfig.blackbox_device) { + case BLACKBOX_DEVICE_SERIAL: + return isSerialTransmitBufferEmpty(blackboxPort); + +#ifdef FLASHFS + case BLACKBOX_DEVICE_FLASH: + flashfsFlushSync(); + return true; +#endif + + default: + return false; + } } diff --git a/src/main/blackbox/blackbox_io.h b/src/main/blackbox/blackbox_io.h index 5abacecfa..4692b0d41 100644 --- a/src/main/blackbox/blackbox_io.h +++ b/src/main/blackbox/blackbox_io.h @@ -20,6 +20,9 @@ #include #include +#define BLACKBOX_DEVICE_SERIAL 0 +#define BLACKBOX_DEVICE_FLASH 1 + uint8_t blackboxWriteChunkSize; void blackboxWrite(uint8_t value); diff --git a/src/main/config/config.c b/src/main/config/config.c index e99b0eb54..b0e56548b 100644 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -450,6 +450,7 @@ static void resetConf(void) #endif #ifdef BLACKBOX + masterConfig.blackbox_device = 0; masterConfig.blackbox_rate_num = 1; masterConfig.blackbox_rate_denom = 1; #endif diff --git a/src/main/config/config_master.h b/src/main/config/config_master.h index bacb7b5a7..990654833 100644 --- a/src/main/config/config_master.h +++ b/src/main/config/config_master.h @@ -85,6 +85,7 @@ typedef struct master_t { uint8_t current_profile_index; controlRateConfig_t controlRateProfiles[MAX_CONTROL_RATE_PROFILE_COUNT]; + uint8_t blackbox_device; uint8_t blackbox_rate_num; uint8_t blackbox_rate_denom; diff --git a/src/main/io/flashfs.c b/src/main/io/flashfs.c index 015738eb3..d027bd3fc 100644 --- a/src/main/io/flashfs.c +++ b/src/main/io/flashfs.c @@ -131,17 +131,14 @@ static void flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSizes, { const flashGeometry_t *geometry = m25p16_getGeometry(); - uint32_t bytesTotalToWrite = 0; - uint32_t bytesTotalRemaining; + uint32_t bytesTotalRemaining = 0; int i; for (i = 0; i < bufferCount; i++) { - bytesTotalToWrite += bufferSizes[i]; + bytesTotalRemaining += bufferSizes[i]; } - bytesTotalRemaining = bytesTotalToWrite; - while (bytesTotalRemaining > 0) { uint32_t bytesTotalThisIteration; uint32_t bytesRemainThisIteration; @@ -188,7 +185,7 @@ static void flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSizes, bytesTotalRemaining -= bytesTotalThisIteration; // Advance the cursor in the file system to match the bytes we wrote - flashfsSetTailAddress(tailAddress + bytesTotalToWrite); + flashfsSetTailAddress(tailAddress + bytesTotalThisIteration); } } @@ -219,6 +216,7 @@ static void flashfsGetDirtyDataBuffers(uint8_t const *buffers[], uint32_t buffer void flashfsFlushAsync() { if (bufferHead == bufferTail) { + shouldFlush = false; return; // Nothing to flush } @@ -230,6 +228,8 @@ void flashfsFlushAsync() flashfsWriteBuffers(buffers, bufferSizes, 2); flashfsClearBuffer(); + + shouldFlush = false; } else { shouldFlush = true; } @@ -243,8 +243,10 @@ void flashfsFlushAsync() */ void flashfsFlushSync() { - if (bufferHead == bufferTail) + if (bufferHead == bufferTail) { + shouldFlush = false; return; // Nothing to write + } m25p16_waitForReady(10); //TODO caller should customize timeout @@ -273,7 +275,7 @@ void flashfsWriteByte(uint8_t byte) bufferHead = 0; } - if (flashfsTransmitBufferUsed() >= FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN) { + if (shouldFlush || flashfsTransmitBufferUsed() >= FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN) { flashfsFlushAsync(); } } @@ -281,7 +283,7 @@ void flashfsWriteByte(uint8_t byte) void flashfsWrite(const uint8_t *data, unsigned int len) { // Would writing this cause our buffer to reach the flush threshold? If so just write it now - if (len + flashfsTransmitBufferUsed() >= FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN || shouldFlush) { + if (shouldFlush || len + flashfsTransmitBufferUsed() >= FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN) { uint8_t const * buffers[3]; uint32_t bufferSizes[3]; @@ -297,6 +299,8 @@ void flashfsWrite(const uint8_t *data, unsigned int len) // And now our buffer is empty flashfsClearBuffer(); + + return; } // Buffer up the data the user supplied instead of writing it right away diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index f6e2984e0..a980c178d 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -422,6 +422,7 @@ const clivalue_t valueTable[] = { { "i_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDVEL], 0, 200 }, { "d_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDVEL], 0, 200 }, + { "blackbox_device", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_device, 0, 1 }, { "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_num, 1, 32 }, { "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_denom, 1, 32 }, }; @@ -800,7 +801,7 @@ static void cliFlashRead(char *cmdline) flashfsSeekAbs(address); while (length > 0) { - int bytesToRead = length < 32 ? length : 32; + uint32_t bytesToRead = length < 32 ? length : 32; flashfsRead(buffer, bytesToRead); From 388842755874c07bf4a305906f693892858794a2 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Wed, 28 Jan 2015 22:34:40 +1300 Subject: [PATCH 04/15] Use bulk flash writing routine for blackboxPrint() --- src/main/blackbox/blackbox_io.c | 28 +++++++++++++++++++++++----- 1 file changed, 23 insertions(+), 5 deletions(-) diff --git a/src/main/blackbox/blackbox_io.c b/src/main/blackbox/blackbox_io.c index 35fe44eec..8d02787ef 100644 --- a/src/main/blackbox/blackbox_io.c +++ b/src/main/blackbox/blackbox_io.c @@ -1,5 +1,6 @@ #include #include +#include #include "blackbox_io.h" @@ -100,14 +101,31 @@ void blackboxPrintf(char *fmt, ...) // Print the null-terminated string 's' to the serial port and return the number of bytes written int blackboxPrint(const char *s) { - const char *pos = s; + int length; + const uint8_t *pos; - while (*pos) { - blackboxWrite(*pos); - pos++; + switch (masterConfig.blackbox_device) { + +#ifdef FLASHFS + case BLACKBOX_DEVICE_FLASH: + length = strlen(s); + flashfsWrite((const uint8_t*) s, length); + break; +#endif + + case BLACKBOX_DEVICE_SERIAL: + default: + pos = (uint8_t*) s; + while (*pos) { + serialWrite(blackboxPort, *pos); + pos++; + } + + length = pos - (uint8_t*) s; + break; } - return pos - s; + return length; } /** From 3c74ac2c913ec7493f8259a24374fec39a98d306 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Fri, 30 Jan 2015 13:45:05 +1300 Subject: [PATCH 05/15] Make more bulk writes asynchronous where possible, begin MSP impl. --- src/main/io/flashfs.c | 143 ++++++++++++++++++++++++++++----------- src/main/io/serial_cli.c | 13 ++-- src/main/io/serial_msp.c | 80 ++++++++++++++++++++-- 3 files changed, 185 insertions(+), 51 deletions(-) diff --git a/src/main/io/flashfs.c b/src/main/io/flashfs.c index d027bd3fc..0fa74389a 100644 --- a/src/main/io/flashfs.c +++ b/src/main/io/flashfs.c @@ -112,33 +112,43 @@ static uint32_t flashfsTransmitBufferUsed() return FLASHFS_WRITE_BUFFER_SIZE - bufferTail + bufferHead; } -static uint32_t flashfsTransmitBufferRemaining() -{ - return FLASHFS_WRITE_BUFFER_USABLE - flashfsTransmitBufferUsed(); -} - /** - * Waits for the flash device to be ready to accept writes, then write the given buffers to flash sequentially. + * Write the given buffers to flash sequentially at the current tail address, advancing the tail address after + * each write. * - * Advances the address of the beginning of the supplied buffers and reduces the size of the buffers according to how - * many bytes get written. + * In synchronous mode, waits for the flash to become ready before writing so that every byte requested can be written. + * + * In asynchronous mode, if the flash is busy, then the write is aborted and the routine returns immediately. + * In this case the returned number of bytes written will be less than the total amount requested. + * + * Modifies the supplied buffer pointers and sizes to reflect how many bytes remain in each of them. * * bufferCount: the number of buffers provided * buffers: an array of pointers to the beginning of buffers * bufferSizes: an array of the sizes of those buffers + * sync: true if we should wait for the device to be idle before writes, otherwise if the device is busy the + * write will be aborted and this routine will return immediately. + * + * Returns the number of bytes written */ -static void flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSizes, int bufferCount) +static uint32_t flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSizes, int bufferCount, bool sync) { const flashGeometry_t *geometry = m25p16_getGeometry(); - uint32_t bytesTotalRemaining = 0; + uint32_t bytesTotal = 0; int i; for (i = 0; i < bufferCount; i++) { - bytesTotalRemaining += bufferSizes[i]; + bytesTotal += bufferSizes[i]; } + if (!sync && !m25p16_isReady()) { + return 0; + } + + uint32_t bytesTotalRemaining = bytesTotal; + while (bytesTotalRemaining > 0) { uint32_t bytesTotalThisIteration; uint32_t bytesRemainThisIteration; @@ -186,7 +196,16 @@ static void flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSizes, // Advance the cursor in the file system to match the bytes we wrote flashfsSetTailAddress(tailAddress + bytesTotalThisIteration); + + /* + * We'll have to wait for that write to complete before we can issue the next one, so if + * the user requested asynchronous writes, break now. + */ + if (!sync) + break; } + + return bytesTotal - bytesTotalRemaining; } /* @@ -209,6 +228,22 @@ static void flashfsGetDirtyDataBuffers(uint8_t const *buffers[], uint32_t buffer } } +/** + * Called after bytes have been written from the buffer to advance the position of the tail by the given amount. + */ +static void flashfsAdvanceTailInBuffer(uint32_t delta) +{ + bufferTail += delta; + + if (bufferTail > FLASHFS_WRITE_BUFFER_SIZE) { + bufferTail -= FLASHFS_WRITE_BUFFER_SIZE; + } + + if (bufferTail == bufferHead) { + flashfsClearBuffer(); + } +} + /** * If the flash is ready to accept writes, flush the buffer to it, otherwise schedule * a flush for later and return immediately. @@ -220,19 +255,15 @@ void flashfsFlushAsync() return; // Nothing to flush } - if (m25p16_isReady()) { - uint8_t const * buffers[2]; - uint32_t bufferSizes[2]; + uint8_t const * buffers[2]; + uint32_t bufferSizes[2]; + uint32_t bytesWritten; - flashfsGetDirtyDataBuffers(buffers, bufferSizes); - flashfsWriteBuffers(buffers, bufferSizes, 2); + flashfsGetDirtyDataBuffers(buffers, bufferSizes); + bytesWritten = flashfsWriteBuffers(buffers, bufferSizes, 2, false); + flashfsAdvanceTailInBuffer(bytesWritten); - flashfsClearBuffer(); - - shouldFlush = false; - } else { - shouldFlush = true; - } + shouldFlush = bufferTail != bufferHead; } /** @@ -248,9 +279,14 @@ void flashfsFlushSync() return; // Nothing to write } - m25p16_waitForReady(10); //TODO caller should customize timeout + uint8_t const * buffers[2]; + uint32_t bufferSizes[2]; - flashfsFlushAsync(); + flashfsGetDirtyDataBuffers(buffers, bufferSizes); + flashfsWriteBuffers(buffers, bufferSizes, 2, true); + + // We've written our entire buffer now: + flashfsClearBuffer(); } void flashfsSeekAbs(uint32_t offset) @@ -282,25 +318,56 @@ void flashfsWriteByte(uint8_t byte) void flashfsWrite(const uint8_t *data, unsigned int len) { - // Would writing this cause our buffer to reach the flush threshold? If so just write it now - if (shouldFlush || len + flashfsTransmitBufferUsed() >= FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN) { - uint8_t const * buffers[3]; - uint32_t bufferSizes[3]; + uint8_t const * buffers[3]; + uint32_t bufferSizes[3]; - // There could be two dirty buffers to write out already: - flashfsGetDirtyDataBuffers(buffers, bufferSizes); + // There could be two dirty buffers to write out already: + flashfsGetDirtyDataBuffers(buffers, bufferSizes); - // Plus the buffer the user supplied: - buffers[2] = data; - bufferSizes[2] = len; + // Plus the buffer the user supplied: + buffers[2] = data; + bufferSizes[2] = len; - // Write all three buffers through to the flash - flashfsWriteBuffers(buffers, bufferSizes, 3); + /* + * Would writing this data to our buffer cause our buffer to reach the flush threshold? If so try to write through + * to the flash now + */ + if (shouldFlush || bufferSizes[0] + bufferSizes[1] + bufferSizes[2] >= FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN) { + uint32_t bytesWritten; - // And now our buffer is empty - flashfsClearBuffer(); + // Attempt to write all three buffers through to the flash asynchronously + bytesWritten = flashfsWriteBuffers(buffers, bufferSizes, 3, false); - return; + if (bufferSizes[0] == 0 && bufferSizes[1] == 0) { + // We wrote all the data that was previously buffered + flashfsClearBuffer(); + + if (bufferSizes[2] == 0) { + // And we wrote all the data the user supplied! Job done! + return; + } + } else { + // We only wrote a portion of the old data, so advance the tail to remove the bytes we did write from the buffer + flashfsAdvanceTailInBuffer(bytesWritten); + } + + if (bufferSizes[0] + bufferSizes[1] + bufferSizes[2] > FLASHFS_WRITE_BUFFER_USABLE) { + /* + * We don't have enough room to store the new data in the buffer without blocking waiting for the flash to + * become ready, so we're forced to write it through synchronously. + * + * TODO we can skip this code and just drop the data for this write instead if the caller wants to + * prioritize predictable response time over reliable data delivery (i.e. sync/async) + */ + flashfsWriteBuffers(buffers, bufferSizes, 3, true); + flashfsClearBuffer(); + + return; + } + + // Fall through and add the remainder of the incoming data to our buffer + data = buffers[2]; + len = bufferSizes[2]; } // Buffer up the data the user supplied instead of writing it right away diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index a980c178d..9a20e7e05 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -114,7 +114,7 @@ static void cliMixer(char *cmdline); #ifdef FLASHFS static void cliFlashIdent(char *cmdline); -static void cliFlashEraseSector(char *cmdline); +static void cliFlashErase(char *cmdline); static void cliFlashWrite(char *cmdline); static void cliFlashRead(char *cmdline); #endif @@ -175,7 +175,7 @@ const clicmd_t cmdTable[] = { { "exit", "", cliExit }, { "feature", "list or -val or val", cliFeature }, #ifdef FLASHFS - { "flash_erase_sector", "erase flash sector at the given address", cliFlashEraseSector }, + { "flash_erase", "erase flash chip", cliFlashErase }, { "flash_ident", "get flash chip details", cliFlashIdent }, { "flash_read", "read text from the given address", cliFlashRead }, { "flash_write", "write text to the given address", cliFlashWrite }, @@ -757,12 +757,13 @@ static void cliFlashIdent(char *cmdline) layout->sectors, layout->sectorSize, layout->pagesPerSector, layout->pageSize, layout->totalSize); } -static void cliFlashEraseSector(char *cmdline) +static void cliFlashErase(char *cmdline) { - uint32_t address = atoi(cmdline); + UNUSED(cmdline); - flashfsEraseRange(address, address + 1); - printf("Erased sector at %u.\r\n", address); + printf("Erasing, please wait...\r\n"); + flashfsEraseCompletely(); + printf("Erased flash chip.\r\n"); } static void cliFlashWrite(char *cmdline) diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index a9eff4df2..3a6ff18e7 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -53,6 +53,7 @@ #include "io/gimbal.h" #include "io/serial.h" #include "io/ledstrip.h" +#include "io/flashfs.h" #include "telemetry/telemetry.h" #include "sensors/boardalignment.h" #include "sensors/sensors.h" @@ -121,7 +122,7 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es #define MSP_PROTOCOL_VERSION 0 #define API_VERSION_MAJOR 1 // increment when major changes are made -#define API_VERSION_MINOR 4 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR +#define API_VERSION_MINOR 5 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR #define API_VERSION_LENGTH 2 @@ -219,6 +220,10 @@ const char *boardIdentifier = TARGET_BOARD_IDENTIFIER; // DEPRECATED - Use MSP_BUILD_INFO instead #define MSP_BF_BUILD_INFO 69 //out message build date as well as some space for future expansion +#define MSP_DATAFLASH_SUMMARY 70 //out message - get description of dataflash chip +#define MSP_DATAFLASH_READ 71 //out message - get content of dataflash chip +#define MSP_DATAFLASH_ERASE 72 //in message - erase dataflash chip + // // Multwii original MSP commands // @@ -421,24 +426,24 @@ uint32_t read32(void) return t; } -void headSerialResponse(uint8_t err, uint8_t s) +void headSerialResponse(uint8_t err, uint8_t responseBodySize) { serialize8('$'); serialize8('M'); serialize8(err ? '!' : '>'); currentPort->checksum = 0; // start calculating a new checksum - serialize8(s); + serialize8(responseBodySize); serialize8(currentPort->cmdMSP); } -void headSerialReply(uint8_t s) +void headSerialReply(uint8_t responseBodySize) { - headSerialResponse(0, s); + headSerialResponse(0, responseBodySize); } -void headSerialError(uint8_t s) +void headSerialError(uint8_t responseBodySize) { - headSerialResponse(1, s); + headSerialResponse(1, responseBodySize); } void tailSerialReply(void) @@ -518,6 +523,44 @@ reset: } } +void serializeDataflashSummaryReply(void) +{ +#ifdef FLASHFS + const flashGeometry_t *geometry = flashfsGetGeometry(); + headSerialReply(2 * 4); + serialize32(geometry->sectors); + serialize32(geometry->totalSize); +#else + headSerialReply(2 * 4); + serialize32(0); + serialize32(0); +#endif +} + +#ifdef FLASHFS +void serializeDataflashReadReply(uint32_t address, uint8_t size) +{ + enum { DATAFLASH_READ_REPLY_CHUNK_SIZE = 128 }; + + uint8_t buffer[DATAFLASH_READ_REPLY_CHUNK_SIZE]; + + if (size > DATAFLASH_READ_REPLY_CHUNK_SIZE) { + size = DATAFLASH_READ_REPLY_CHUNK_SIZE; + } + + headSerialReply(4 + size); + + serialize32(address); + + flashfsSeekAbs(address); + flashfsRead(buffer, size); + + for (int i = 0; i < size; i++) { + serialize8(buffer[i]); + } +} +#endif + static void resetMspPort(mspPort_t *mspPortToReset, serialPort_t *serialPort, mspPortUsage_e usage) { memset(mspPortToReset, 0, sizeof(mspPort_t)); @@ -1128,6 +1171,22 @@ static bool processOutCommand(uint8_t cmdMSP) } break; #endif + + case MSP_DATAFLASH_SUMMARY: + serializeDataflashSummaryReply(); + break; + +#ifdef FLASHFS + case MSP_DATAFLASH_READ: + { + uint32_t readAddress = read32(); + uint8_t readSize = read8(); + + serializeDataflashReadReply(readAddress, readSize); + } + break; +#endif + case MSP_BF_BUILD_INFO: headSerialReply(11 + 4 + 4); for (i = 0; i < 11; i++) @@ -1333,6 +1392,13 @@ static bool processInCommand(void) writeEEPROM(); readEEPROM(); break; + +#ifdef FLASHFS + case MSP_DATAFLASH_ERASE: + flashfsEraseCompletely(); + break; +#endif + #ifdef GPS case MSP_SET_RAW_GPS: if (read8()) { From f7d227a208d8373149f49d951b515c55f8874da8 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Sat, 31 Jan 2015 00:35:17 +1300 Subject: [PATCH 06/15] Successfully blackbox logged 46kB of flawless log data on the bench Data read back using MSP --- src/main/io/flashfs.c | 14 +++++++++++--- src/main/io/serial_msp.c | 9 +++++---- 2 files changed, 16 insertions(+), 7 deletions(-) diff --git a/src/main/io/flashfs.c b/src/main/io/flashfs.c index 0fa74389a..cb3c19310 100644 --- a/src/main/io/flashfs.c +++ b/src/main/io/flashfs.c @@ -401,9 +401,17 @@ void flashfsWrite(const uint8_t *data, unsigned int len) */ int flashfsRead(uint8_t *data, unsigned int len) { - int result = m25p16_readBytes(tailAddress, data, len); + int bytesRead; - flashfsSetTailAddress(tailAddress + result); + // Did caller try to read past the end of the volume? + if (tailAddress + len > flashfsGetSize()) { + // Truncate their request + len = flashfsGetSize() - tailAddress; + } - return result; + bytesRead = m25p16_readBytes(tailAddress, data, len); + + flashfsSetTailAddress(tailAddress + bytesRead); + + return bytesRead; } diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index 0c4481f0b..895dd6a39 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -551,6 +551,7 @@ static void serializeDataflashReadReply(uint32_t address, uint8_t size) enum { DATAFLASH_READ_REPLY_CHUNK_SIZE = 128 }; uint8_t buffer[DATAFLASH_READ_REPLY_CHUNK_SIZE]; + int bytesRead; if (size > DATAFLASH_READ_REPLY_CHUNK_SIZE) { size = DATAFLASH_READ_REPLY_CHUNK_SIZE; @@ -561,9 +562,10 @@ static void serializeDataflashReadReply(uint32_t address, uint8_t size) serialize32(address); flashfsSeekAbs(address); - flashfsRead(buffer, size); + // bytesRead will be lower than that requested if we reach end of volume + bytesRead = flashfsRead(buffer, size); - for (int i = 0; i < size; i++) { + for (int i = 0; i < bytesRead; i++) { serialize8(buffer[i]); } } @@ -1203,9 +1205,8 @@ static bool processOutCommand(uint8_t cmdMSP) case MSP_DATAFLASH_READ: { uint32_t readAddress = read32(); - uint8_t readSize = read8(); - serializeDataflashReadReply(readAddress, readSize); + serializeDataflashReadReply(readAddress, 128); } break; #endif From 5651e65a0b70f7624cebbd5d3a1f9f54ece232e8 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Tue, 10 Feb 2015 13:44:18 +1300 Subject: [PATCH 07/15] Add support for discovering beginning of free space on flash chip --- src/main/drivers/flash_m25p16.c | 4 +- src/main/io/flashfs.c | 119 +++++++++++++++++++++++++++++--- src/main/io/flashfs.h | 6 +- src/main/io/serial_cli.c | 24 ++++--- src/main/io/serial_msp.c | 16 ++--- src/main/main.c | 2 + 6 files changed, 142 insertions(+), 29 deletions(-) diff --git a/src/main/drivers/flash_m25p16.c b/src/main/drivers/flash_m25p16.c index 3eac01041..e977f257e 100644 --- a/src/main/drivers/flash_m25p16.c +++ b/src/main/drivers/flash_m25p16.c @@ -256,7 +256,9 @@ void m25p16_pageProgram(uint32_t address, const uint8_t *data, int length) * Read `length` bytes into the provided `buffer` from the flash starting from the given `address` (which need not lie * on a page boundary). * - * The number of bytes actually read is returned, which can be zero if an error occurred. + * Waits up to DEFAULT_TIMEOUT_MILLIS milliseconds for the flash to become ready before reading. + * + * The number of bytes actually read is returned, which can be zero if an error or timeout occurred. */ int m25p16_readBytes(uint32_t address, uint8_t *buffer, int length) { diff --git a/src/main/io/flashfs.c b/src/main/io/flashfs.c index cb3c19310..4392b37f1 100644 --- a/src/main/io/flashfs.c +++ b/src/main/io/flashfs.c @@ -18,6 +18,10 @@ /** * This provides a stream interface to a flash chip if one is present. * + * On statup, call flashfsInit after initialising the flash chip, in order to init the filesystem. This will + * result in the file pointer being pointed at the first free block found, or at the end of the device if the + * flash chip is full. + * * Note that bits can only be set to 0 when writing, not back to 1 from 0. You must erase sectors in order * to bring bits back to 1 again. */ @@ -39,7 +43,7 @@ static uint8_t flashWriteBuffer[FLASHFS_WRITE_BUFFER_SIZE]; */ static uint8_t bufferHead = 0, bufferTail = 0; -// The position of our tail in the overall flash address space: +// The position of the buffer's tail in the overall flash address space: static uint32_t tailAddress = 0; // The index of the tail within the flash page it is inside static uint16_t tailIndexInPage = 0; @@ -55,7 +59,10 @@ static void flashfsClearBuffer() static void flashfsSetTailAddress(uint32_t address) { tailAddress = address; - tailIndexInPage = tailAddress % m25p16_getGeometry()->pageSize; + + if (m25p16_getGeometry()->pageSize > 0) { + tailIndexInPage = tailAddress % m25p16_getGeometry()->pageSize; + } } void flashfsEraseCompletely() @@ -163,6 +170,10 @@ static uint32_t flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSiz bytesTotalThisIteration = bytesTotalRemaining; } + // Are we at EOF already? Abort. + if (tailAddress >= flashfsGetSize()) + break; + m25p16_pageProgramBegin(tailAddress); bytesRemainThisIteration = bytesTotalThisIteration; @@ -228,6 +239,21 @@ static void flashfsGetDirtyDataBuffers(uint8_t const *buffers[], uint32_t buffer } } +/** + * Get the current offset of the file pointer within the volume. + */ +uint32_t flashfsGetOffset() +{ + uint8_t const * buffers[2]; + uint32_t bufferSizes[2]; + + // Dirty data in the buffers contributes to the offset + + flashfsGetDirtyDataBuffers(buffers, bufferSizes); + + return tailAddress + bufferSizes[0] + bufferSizes[1]; +} + /** * Called after bytes have been written from the buffer to advance the position of the tail by the given amount. */ @@ -395,23 +421,100 @@ void flashfsWrite(const uint8_t *data, unsigned int len) } /** - * Read `len` bytes from the current cursor location into the supplied buffer. + * Read `len` bytes from the given address into the supplied buffer. * * Returns the number of bytes actually read which may be less than that requested. */ -int flashfsRead(uint8_t *data, unsigned int len) +int flashfsReadAbs(uint32_t address, uint8_t *buffer, unsigned int len) { int bytesRead; // Did caller try to read past the end of the volume? - if (tailAddress + len > flashfsGetSize()) { + if (address + len > flashfsGetSize()) { // Truncate their request - len = flashfsGetSize() - tailAddress; + len = flashfsGetSize() - address; } - bytesRead = m25p16_readBytes(tailAddress, data, len); + // Since the read could overlap data in our dirty buffers, force a sync to clear those first + flashfsFlushSync(); - flashfsSetTailAddress(tailAddress + bytesRead); + bytesRead = m25p16_readBytes(address, buffer, len); return bytesRead; } + +/** + * Find the offset of the start of the free space on the device (or the size of the device if it is full). + */ +int flashfsIdentifyStartOfFreeSpace() +{ + /* Find the start of the free space on the device by examining the beginning of blocks with a binary search, + * looking for ones that appear to be erased. We can achieve this with good accuracy because an erased block + * is all bits set to 1, which pretty much never appears in reasonable size substrings of blackbox logs. + * + * To do better we might write a volume header instead, which would mark how much free space remains. But keeping + * a header up to date while logging would incur more writes to the flash, which would consume precious write + * bandwidth and block more often. + */ + + enum { + /* We can choose whatever power of 2 size we like, which determines how much wastage of free space we'll have + * at the end of the last written data. But smaller blocksizes will require more searching. + */ + FREE_BLOCK_SIZE = 65536, + + /* We don't expect valid data to ever contain this many consecutive uint32_t's of all 1 bits: */ + FREE_BLOCK_TEST_SIZE_INTS = 4, // i.e. 16 bytes + FREE_BLOCK_TEST_SIZE_BYTES = FREE_BLOCK_TEST_SIZE_INTS * sizeof(uint32_t), + }; + + union { + uint8_t bytes[FREE_BLOCK_TEST_SIZE_BYTES]; + uint32_t ints[FREE_BLOCK_TEST_SIZE_INTS]; + } testBuffer; + + int left = 0; + int right = flashfsGetSize() / FREE_BLOCK_SIZE; + int mid, result = right; + int i; + bool blockErased; + + while (left < right) { + mid = (left + right) / 2; + + m25p16_readBytes(mid * FREE_BLOCK_SIZE, testBuffer.bytes, FREE_BLOCK_TEST_SIZE_BYTES); + + // Checking the buffer 4 bytes at a time like this is probably faster than byte-by-byte, but I didn't benchmark it :) + blockErased = true; + for (i = 0; i < FREE_BLOCK_TEST_SIZE_INTS; i++) { + if (testBuffer.ints[i] != 0xFFFFFFFF) { + blockErased = false; + break; + } + } + + if (blockErased) { + /* This erased block might be the leftmost erased block in the volume, but we'll need to continue the + * search leftwards to find out: + */ + result = mid; + + right = mid; + } else { + left = mid + 1; + } + } + + return result * FREE_BLOCK_SIZE; +} + +/** + * Call after initializing the flash chip in order to set up the filesystem. + */ +void flashfsInit() +{ + if (flashfsGetSize() > 0) { + // Start the file pointer off at the beginning of free space so caller can start writing immediately + flashfsSeekAbs(flashfsIdentifyStartOfFreeSpace()); + } +} diff --git a/src/main/io/flashfs.h b/src/main/io/flashfs.h index a9f8403da..fa72bc6bf 100644 --- a/src/main/io/flashfs.h +++ b/src/main/io/flashfs.h @@ -31,6 +31,8 @@ void flashfsEraseCompletely(); void flashfsEraseRange(uint32_t start, uint32_t end); uint32_t flashfsGetSize(); +uint32_t flashfsGetOffset(); +int flashfsIdentifyStartOfFreeSpace(); const flashGeometry_t* flashfsGetGeometry(); void flashfsSeekAbs(uint32_t offset); @@ -39,7 +41,9 @@ void flashfsSeekRel(int32_t offset); void flashfsWriteByte(uint8_t byte); void flashfsWrite(const uint8_t *data, unsigned int len); -int flashfsRead(uint8_t *data, unsigned int len); +int flashfsReadAbs(uint32_t offset, uint8_t *data, unsigned int len); void flashfsFlushAsync(); void flashfsFlushSync(); + +void flashfsInit(); diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index a64e416ed..794f8aec6 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -753,8 +753,8 @@ static void cliFlashIdent(char *cmdline) UNUSED(cmdline); - printf("Flash sectors=%u, sectorSize=%u, pagesPerSector=%u, pageSize=%u, totalSize=%u\r\n", - layout->sectors, layout->sectorSize, layout->pagesPerSector, layout->pageSize, layout->totalSize); + printf("Flash sectors=%u, sectorSize=%u, pagesPerSector=%u, pageSize=%u, totalSize=%u, usedSize=%u\r\n", + layout->sectors, layout->sectorSize, layout->pagesPerSector, layout->pageSize, layout->totalSize, flashfsGetOffset()); } static void cliFlashErase(char *cmdline) @@ -786,7 +786,7 @@ static void cliFlashRead(char *cmdline) { uint32_t address = atoi(cmdline); uint32_t length; - uint32_t i; + int i; uint8_t buffer[32]; @@ -799,18 +799,22 @@ static void cliFlashRead(char *cmdline) printf("Reading %u bytes at %u:\r\n", length, address); - flashfsSeekAbs(address); - while (length > 0) { - uint32_t bytesToRead = length < 32 ? length : 32; + int bytesRead; - flashfsRead(buffer, bytesToRead); + bytesRead = flashfsReadAbs(address, buffer, length < sizeof(buffer) ? length : sizeof(buffer)); - for (i = 0; i < bytesToRead; i++) { - printf("%c", (char) buffer[i]); + for (i = 0; i < bytesRead; i++) { + cliWrite(buffer[i]); } - length -= bytesToRead; + length -= bytesRead; + address += bytesRead; + + if (bytesRead == 0) { + //Assume we reached the end of the volume or something fatal happened + break; + } } printf("\r\n"); } diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index 895dd6a39..b890f12bd 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -533,13 +533,14 @@ reset: static void serializeDataflashSummaryReply(void) { + headSerialReply(3 * 4); #ifdef FLASHFS const flashGeometry_t *geometry = flashfsGetGeometry(); - headSerialReply(2 * 4); serialize32(geometry->sectors); serialize32(geometry->totalSize); + serialize32(flashfsGetOffset()); // Effectively the current number of bytes stored on the volume #else - headSerialReply(2 * 4); + serialize32(0); serialize32(0); serialize32(0); #endif @@ -548,22 +549,19 @@ static void serializeDataflashSummaryReply(void) #ifdef FLASHFS static void serializeDataflashReadReply(uint32_t address, uint8_t size) { - enum { DATAFLASH_READ_REPLY_CHUNK_SIZE = 128 }; - - uint8_t buffer[DATAFLASH_READ_REPLY_CHUNK_SIZE]; + uint8_t buffer[128]; int bytesRead; - if (size > DATAFLASH_READ_REPLY_CHUNK_SIZE) { - size = DATAFLASH_READ_REPLY_CHUNK_SIZE; + if (size > sizeof(buffer)) { + size = sizeof(buffer); } headSerialReply(4 + size); serialize32(address); - flashfsSeekAbs(address); // bytesRead will be lower than that requested if we reach end of volume - bytesRead = flashfsRead(buffer, size); + bytesRead = flashfsReadAbs(address, buffer, size); for (int i = 0; i < bytesRead; i++) { serialize8(buffer[i]); diff --git a/src/main/main.c b/src/main/main.c index ecea01c39..fe3f605a7 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -50,6 +50,7 @@ #include "flight/mixer.h" #include "io/serial.h" +#include "io/flashfs.h" #include "flight/failsafe.h" #include "flight/navigation.h" @@ -355,6 +356,7 @@ void init(void) // naze32 rev5 and above have 16mbit of flash available m25p16_init(); #endif + flashfsInit(); #endif #ifdef BLACKBOX From 80ea5e441977471de42dbbb68ef889d44ea586f9 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Fri, 13 Feb 2015 20:28:19 +1300 Subject: [PATCH 08/15] Add flash ready state to MSP response, add flash async block write --- src/main/blackbox/blackbox.c | 3 +- src/main/blackbox/blackbox_io.c | 4 +- src/main/io/flashfs.c | 84 +++++++++++++++++++++------------ src/main/io/flashfs.h | 4 +- src/main/io/serial_cli.c | 2 +- src/main/io/serial_msp.c | 4 +- 6 files changed, 65 insertions(+), 36 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index de439bed1..fb07315bf 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -789,7 +789,8 @@ static bool sendFieldDefinition(const char * const *headerNames, unsigned int he charsWritten = blackboxPrint("H Field "); charsWritten += blackboxPrint(headerNames[xmitState.headerIndex]); - charsWritten += blackboxPrint(":"); + blackboxWrite(':'); + charsWritten++; xmitState.u.fieldIndex++; needComma = false; diff --git a/src/main/blackbox/blackbox_io.c b/src/main/blackbox/blackbox_io.c index 8d02787ef..2bf8a54b9 100644 --- a/src/main/blackbox/blackbox_io.c +++ b/src/main/blackbox/blackbox_io.c @@ -73,7 +73,7 @@ void blackboxWrite(uint8_t value) switch (masterConfig.blackbox_device) { #ifdef FLASHFS case BLACKBOX_DEVICE_FLASH: - flashfsWriteByte(value); + flashfsWriteByte(value); // Write byte asynchronously break; #endif case BLACKBOX_DEVICE_SERIAL: @@ -109,7 +109,7 @@ int blackboxPrint(const char *s) #ifdef FLASHFS case BLACKBOX_DEVICE_FLASH: length = strlen(s); - flashfsWrite((const uint8_t*) s, length); + flashfsWrite((const uint8_t*) s, length, false); // Write asynchronously break; #endif diff --git a/src/main/io/flashfs.c b/src/main/io/flashfs.c index 4392b37f1..c80de7c37 100644 --- a/src/main/io/flashfs.c +++ b/src/main/io/flashfs.c @@ -28,6 +28,7 @@ #include #include +#include #include "drivers/flash_m25p16.h" #include "flashfs.h" @@ -56,6 +57,11 @@ static void flashfsClearBuffer() shouldFlush = false; } +static bool flashfsBufferIsEmpty() +{ + return bufferTail == bufferHead; +} + static void flashfsSetTailAddress(uint32_t address) { tailAddress = address; @@ -101,6 +107,14 @@ void flashfsEraseRange(uint32_t start, uint32_t end) } } +/** + * Return true if the flash is not currently occupied with an operation. + */ +bool flashfsIsReady() +{ + return m25p16_isReady(); +} + uint32_t flashfsGetSize() { return m25p16_getGeometry()->totalSize; @@ -261,12 +275,13 @@ static void flashfsAdvanceTailInBuffer(uint32_t delta) { bufferTail += delta; - if (bufferTail > FLASHFS_WRITE_BUFFER_SIZE) { + // Wrap tail around the end of the buffer + if (bufferTail >= FLASHFS_WRITE_BUFFER_SIZE) { bufferTail -= FLASHFS_WRITE_BUFFER_SIZE; } - if (bufferTail == bufferHead) { - flashfsClearBuffer(); + if (flashfsBufferIsEmpty()) { + flashfsClearBuffer(); // Bring buffer pointers back to the start to be tidier } } @@ -276,7 +291,7 @@ static void flashfsAdvanceTailInBuffer(uint32_t delta) */ void flashfsFlushAsync() { - if (bufferHead == bufferTail) { + if (flashfsBufferIsEmpty()) { shouldFlush = false; return; // Nothing to flush } @@ -289,7 +304,7 @@ void flashfsFlushAsync() bytesWritten = flashfsWriteBuffers(buffers, bufferSizes, 2, false); flashfsAdvanceTailInBuffer(bytesWritten); - shouldFlush = bufferTail != bufferHead; + shouldFlush = !flashfsBufferIsEmpty(); } /** @@ -300,9 +315,9 @@ void flashfsFlushAsync() */ void flashfsFlushSync() { - if (bufferHead == bufferTail) { + if (flashfsBufferIsEmpty()) { shouldFlush = false; - return; // Nothing to write + return; // Nothing to flush } uint8_t const * buffers[2]; @@ -329,6 +344,9 @@ void flashfsSeekRel(int32_t offset) flashfsSetTailAddress(tailAddress + offset); } +/** + * Write the given byte asynchronously to the flash. If the buffer overflows, data is silently discarded. + */ void flashfsWriteByte(uint8_t byte) { flashWriteBuffer[bufferHead++] = byte; @@ -342,7 +360,13 @@ void flashfsWriteByte(uint8_t byte) } } -void flashfsWrite(const uint8_t *data, unsigned int len) +/** + * Write the given buffer to the flash either synchronously or asynchronously depending on the 'sync' parameter. + * + * If writing asynchronously, data will be silently discarded if the buffer overflows. + * If writing synchronously, the routine will block waiting for the flash to become ready so will never drop data. + */ +void flashfsWrite(const uint8_t *data, unsigned int len, bool sync) { uint8_t const * buffers[3]; uint32_t bufferSizes[3]; @@ -377,16 +401,18 @@ void flashfsWrite(const uint8_t *data, unsigned int len) flashfsAdvanceTailInBuffer(bytesWritten); } + // Is the remainder of the data to be written too big to fit in the buffers? if (bufferSizes[0] + bufferSizes[1] + bufferSizes[2] > FLASHFS_WRITE_BUFFER_USABLE) { - /* - * We don't have enough room to store the new data in the buffer without blocking waiting for the flash to - * become ready, so we're forced to write it through synchronously. - * - * TODO we can skip this code and just drop the data for this write instead if the caller wants to - * prioritize predictable response time over reliable data delivery (i.e. sync/async) - */ - flashfsWriteBuffers(buffers, bufferSizes, 3, true); - flashfsClearBuffer(); + if (sync) { + // Write it through synchronously + flashfsWriteBuffers(buffers, bufferSizes, 3, true); + flashfsClearBuffer(); + } else { + /* + * Silently drop the data the user asked to write (i.e. no-op) since we can't buffer it and they + * requested async. + */ + } return; } @@ -399,24 +425,22 @@ void flashfsWrite(const uint8_t *data, unsigned int len) // Buffer up the data the user supplied instead of writing it right away // First write the portion before we wrap around the end of the circular buffer - unsigned int bufferBytesBeforeLoop = FLASHFS_WRITE_BUFFER_SIZE - bufferHead; + unsigned int bufferBytesBeforeWrap = FLASHFS_WRITE_BUFFER_SIZE - bufferHead; - unsigned int firstPortion = len < bufferBytesBeforeLoop ? len : bufferBytesBeforeLoop; - unsigned int remainder = firstPortion < len ? len - firstPortion : 0; + unsigned int firstPortion = len < bufferBytesBeforeWrap ? len : bufferBytesBeforeWrap; - for (unsigned int i = 0; i < firstPortion; i++) { - flashWriteBuffer[bufferHead++] = *data; - data++; - } + memcpy(flashWriteBuffer + bufferHead, data, firstPortion); + bufferHead += firstPortion; + + data += firstPortion; + len -= firstPortion; + + // If we wrap the head around, write the remainder to the start of the buffer (if any) if (bufferHead == FLASHFS_WRITE_BUFFER_SIZE) { - bufferHead = 0; - } + memcpy(flashWriteBuffer + 0, data, len); - // Then the remainder (if any) - for (unsigned int i = 0; i < remainder; i++) { - flashWriteBuffer[bufferHead++] = *data; - data++; + bufferHead = len; } } diff --git a/src/main/io/flashfs.h b/src/main/io/flashfs.h index fa72bc6bf..bbea1e058 100644 --- a/src/main/io/flashfs.h +++ b/src/main/io/flashfs.h @@ -39,7 +39,7 @@ void flashfsSeekAbs(uint32_t offset); void flashfsSeekRel(int32_t offset); void flashfsWriteByte(uint8_t byte); -void flashfsWrite(const uint8_t *data, unsigned int len); +void flashfsWrite(const uint8_t *data, unsigned int len, bool sync); int flashfsReadAbs(uint32_t offset, uint8_t *data, unsigned int len); @@ -47,3 +47,5 @@ void flashfsFlushAsync(); void flashfsFlushSync(); void flashfsInit(); + +bool flashfsIsReady(); diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 794f8aec6..af40ec730 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -775,7 +775,7 @@ static void cliFlashWrite(char *cmdline) printf("Missing text to write.\r\n"); } else { flashfsSeekAbs(address); - flashfsWrite((uint8_t*)text, strlen(text)); + flashfsWrite((uint8_t*)text, strlen(text), true); flashfsFlushSync(); printf("Wrote %u bytes at %u.\r\n", strlen(text), address); diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index b890f12bd..c5e01605e 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -533,13 +533,15 @@ reset: static void serializeDataflashSummaryReply(void) { - headSerialReply(3 * 4); + headSerialReply(1 + 3 * 4); #ifdef FLASHFS const flashGeometry_t *geometry = flashfsGetGeometry(); + serialize8(flashfsIsReady() ? 1 : 0); serialize32(geometry->sectors); serialize32(geometry->totalSize); serialize32(flashfsGetOffset()); // Effectively the current number of bytes stored on the volume #else + serialize8(0); serialize32(0); serialize32(0); serialize32(0); From 3b8e05fb46d612a75b6f5b7ca332563044be12f9 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Fri, 13 Feb 2015 21:56:36 +1300 Subject: [PATCH 09/15] Stop Blackbox logging when flash fills up --- src/main/blackbox/blackbox.c | 5 +++++ src/main/blackbox/blackbox_io.c | 19 ++++++++++++++++++- src/main/blackbox/blackbox_io.h | 1 + src/main/io/flashfs.c | 18 ++++++++++++++++-- src/main/io/flashfs.h | 1 + 5 files changed, 41 insertions(+), 3 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index fb07315bf..f03eb2b0e 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1129,6 +1129,11 @@ void handleBlackbox(void) default: break; } + + // Did we run out of room on the device? Stop! + if (isBlackboxDeviceFull()) { + blackboxSetState(BLACKBOX_STATE_STOPPED); + } } static bool canUseBlackboxWithCurrentConfiguration(void) diff --git a/src/main/blackbox/blackbox_io.c b/src/main/blackbox/blackbox_io.c index 2bf8a54b9..f6a80ebf8 100644 --- a/src/main/blackbox/blackbox_io.c +++ b/src/main/blackbox/blackbox_io.c @@ -457,8 +457,9 @@ bool blackboxDeviceOpen(void) break; #ifdef FLASHFS case BLACKBOX_DEVICE_FLASH: - if (flashfsGetSize() == 0) + if (flashfsGetSize() == 0 || isBlackboxDeviceFull()) { return false; + } return true; break; @@ -509,3 +510,19 @@ bool isBlackboxDeviceIdle(void) return false; } } + +bool isBlackboxDeviceFull(void) +{ + switch (masterConfig.blackbox_device) { + case BLACKBOX_DEVICE_SERIAL: + return false; + +#ifdef FLASHFS + case BLACKBOX_DEVICE_FLASH: + return flashfsIsEOF(); +#endif + + default: + return false; + } +} diff --git a/src/main/blackbox/blackbox_io.h b/src/main/blackbox/blackbox_io.h index 4692b0d41..219aab730 100644 --- a/src/main/blackbox/blackbox_io.h +++ b/src/main/blackbox/blackbox_io.h @@ -42,3 +42,4 @@ bool blackboxDeviceOpen(void); void blackboxDeviceClose(void); bool isBlackboxDeviceIdle(void); +bool isBlackboxDeviceFull(void); diff --git a/src/main/io/flashfs.c b/src/main/io/flashfs.c index c80de7c37..a4f8cefc3 100644 --- a/src/main/io/flashfs.c +++ b/src/main/io/flashfs.c @@ -18,12 +18,15 @@ /** * This provides a stream interface to a flash chip if one is present. * - * On statup, call flashfsInit after initialising the flash chip, in order to init the filesystem. This will + * On statup, call flashfsInit() after initialising the flash chip in order to init the filesystem. This will * result in the file pointer being pointed at the first free block found, or at the end of the device if the * flash chip is full. * * Note that bits can only be set to 0 when writing, not back to 1 from 0. You must erase sectors in order * to bring bits back to 1 again. + * + * In future, we can add support for multiple different flash chips by adding a flash device driver vtable + * and make calls through that, at the moment flashfs just calls m25p16_* routines explicitly. */ #include @@ -185,8 +188,12 @@ static uint32_t flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSiz } // Are we at EOF already? Abort. - if (tailAddress >= flashfsGetSize()) + if (flashfsIsEOF()) { + // May as well throw away any buffered data + flashfsClearBuffer(); + break; + } m25p16_pageProgramBegin(tailAddress); @@ -532,6 +539,13 @@ int flashfsIdentifyStartOfFreeSpace() return result * FREE_BLOCK_SIZE; } +/** + * Returns true if the file pointer is at the end of the device. + */ +bool flashfsIsEOF() { + return tailAddress >= flashfsGetSize(); +} + /** * Call after initializing the flash chip in order to set up the filesystem. */ diff --git a/src/main/io/flashfs.h b/src/main/io/flashfs.h index bbea1e058..840f56044 100644 --- a/src/main/io/flashfs.h +++ b/src/main/io/flashfs.h @@ -49,3 +49,4 @@ void flashfsFlushSync(); void flashfsInit(); bool flashfsIsReady(); +bool flashfsIsEOF(); From 6423ac7db140041f174a185985246a642ae4e610 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Sat, 14 Feb 2015 09:45:56 +1300 Subject: [PATCH 10/15] Rename FLASHFS to USE_FLASHFS --- src/main/blackbox/blackbox.c | 2 +- src/main/blackbox/blackbox_io.c | 14 +++++++------- src/main/blackbox/blackbox_io.h | 13 +++++++++++-- src/main/io/serial_cli.c | 6 +++--- src/main/io/serial_msp.c | 8 ++++---- src/main/main.c | 2 +- src/main/target/NAZE/target.h | 2 +- 7 files changed, 28 insertions(+), 19 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index f03eb2b0e..0b5e705f4 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -606,7 +606,7 @@ static void validateBlackboxConfig() masterConfig.blackbox_rate_denom /= div; } - if (!(masterConfig.blackbox_device == BLACKBOX_DEVICE_SERIAL || masterConfig.blackbox_device == BLACKBOX_DEVICE_FLASH)) { + if (masterConfig.blackbox_device >= BLACKBOX_DEVICE_END) { masterConfig.blackbox_device = BLACKBOX_DEVICE_SERIAL; } } diff --git a/src/main/blackbox/blackbox_io.c b/src/main/blackbox/blackbox_io.c index f6a80ebf8..a8971ff72 100644 --- a/src/main/blackbox/blackbox_io.c +++ b/src/main/blackbox/blackbox_io.c @@ -71,7 +71,7 @@ static uint32_t previousBaudRate; void blackboxWrite(uint8_t value) { switch (masterConfig.blackbox_device) { -#ifdef FLASHFS +#ifdef USE_FLASHFS case BLACKBOX_DEVICE_FLASH: flashfsWriteByte(value); // Write byte asynchronously break; @@ -106,7 +106,7 @@ int blackboxPrint(const char *s) switch (masterConfig.blackbox_device) { -#ifdef FLASHFS +#ifdef USE_FLASHFS case BLACKBOX_DEVICE_FLASH: length = strlen(s); flashfsWrite((const uint8_t*) s, length, false); // Write asynchronously @@ -412,7 +412,7 @@ void blackboxDeviceFlush(void) case BLACKBOX_DEVICE_SERIAL: //Presently a no-op on serial, as serial is continuously being drained out of its buffer break; -#ifdef FLASHFS +#ifdef USE_FLASHFS case BLACKBOX_DEVICE_FLASH: flashfsFlushSync(); break; @@ -455,7 +455,7 @@ bool blackboxDeviceOpen(void) return blackboxPort != NULL; break; -#ifdef FLASHFS +#ifdef USE_FLASHFS case BLACKBOX_DEVICE_FLASH: if (flashfsGetSize() == 0 || isBlackboxDeviceFull()) { return false; @@ -486,7 +486,7 @@ void blackboxDeviceClose(void) mspAllocateSerialPorts(&masterConfig.serialConfig); } break; -#ifdef FLASHFS +#ifdef USE_FLASHFS case BLACKBOX_DEVICE_FLASH: flashfsFlushSync(); break; @@ -500,7 +500,7 @@ bool isBlackboxDeviceIdle(void) case BLACKBOX_DEVICE_SERIAL: return isSerialTransmitBufferEmpty(blackboxPort); -#ifdef FLASHFS +#ifdef USE_FLASHFS case BLACKBOX_DEVICE_FLASH: flashfsFlushSync(); return true; @@ -517,7 +517,7 @@ bool isBlackboxDeviceFull(void) case BLACKBOX_DEVICE_SERIAL: return false; -#ifdef FLASHFS +#ifdef USE_FLASHFS case BLACKBOX_DEVICE_FLASH: return flashfsIsEOF(); #endif diff --git a/src/main/blackbox/blackbox_io.h b/src/main/blackbox/blackbox_io.h index 219aab730..8fca16d72 100644 --- a/src/main/blackbox/blackbox_io.h +++ b/src/main/blackbox/blackbox_io.h @@ -20,8 +20,17 @@ #include #include -#define BLACKBOX_DEVICE_SERIAL 0 -#define BLACKBOX_DEVICE_FLASH 1 +#include "target.h" + +typedef enum BlackboxDevice { + BLACKBOX_DEVICE_SERIAL = 0, + +#ifdef USE_FLASHFS + BLACKBOX_DEVICE_FLASH, +#endif + + BLACKBOX_DEVICE_END +} BlackboxDevice; uint8_t blackboxWriteChunkSize; diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index af40ec730..00a01c6c5 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -112,7 +112,7 @@ static void cliColor(char *cmdline); static void cliMixer(char *cmdline); #endif -#ifdef FLASHFS +#ifdef USE_FLASHFS static void cliFlashIdent(char *cmdline); static void cliFlashErase(char *cmdline); static void cliFlashWrite(char *cmdline); @@ -174,7 +174,7 @@ const clicmd_t cmdTable[] = { { "dump", "print configurable settings in a pastable form", cliDump }, { "exit", "", cliExit }, { "feature", "list or -val or val", cliFeature }, -#ifdef FLASHFS +#ifdef USE_FLASHFS { "flash_erase", "erase flash chip", cliFlashErase }, { "flash_ident", "get flash chip details", cliFlashIdent }, { "flash_read", "read text from the given address", cliFlashRead }, @@ -745,7 +745,7 @@ static void cliColor(char *cmdline) } #endif -#ifdef FLASHFS +#ifdef USE_FLASHFS static void cliFlashIdent(char *cmdline) { diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index c5e01605e..94df8ffa7 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -534,7 +534,7 @@ reset: static void serializeDataflashSummaryReply(void) { headSerialReply(1 + 3 * 4); -#ifdef FLASHFS +#ifdef USE_FLASHFS const flashGeometry_t *geometry = flashfsGetGeometry(); serialize8(flashfsIsReady() ? 1 : 0); serialize32(geometry->sectors); @@ -548,7 +548,7 @@ static void serializeDataflashSummaryReply(void) #endif } -#ifdef FLASHFS +#ifdef USE_FLASHFS static void serializeDataflashReadReply(uint32_t address, uint8_t size) { uint8_t buffer[128]; @@ -1201,7 +1201,7 @@ static bool processOutCommand(uint8_t cmdMSP) serializeDataflashSummaryReply(); break; -#ifdef FLASHFS +#ifdef USE_FLASHFS case MSP_DATAFLASH_READ: { uint32_t readAddress = read32(); @@ -1421,7 +1421,7 @@ static bool processInCommand(void) readEEPROM(); break; -#ifdef FLASHFS +#ifdef USE_FLASHFS case MSP_DATAFLASH_ERASE: flashfsEraseCompletely(); break; diff --git a/src/main/main.c b/src/main/main.c index fe3f605a7..814c4de72 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -351,7 +351,7 @@ void init(void) initTelemetry(); #endif -#ifdef FLASHFS +#ifdef USE_FLASHFS #ifdef NAZE // naze32 rev5 and above have 16mbit of flash available m25p16_init(); diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h index 9209583ba..d2f033e52 100644 --- a/src/main/target/NAZE/target.h +++ b/src/main/target/NAZE/target.h @@ -65,7 +65,7 @@ #define MPU6500_CS_PIN NAZE_SPI_CS_PIN #define MPU6500_SPI_INSTANCE NAZE_SPI_INSTANCE -#define FLASHFS +#define USE_FLASHFS #define USE_FLASH_M25P16 From d6911e8b86d204edddb795524d19b522368e3d95 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Sun, 15 Feb 2015 23:23:53 +1300 Subject: [PATCH 11/15] Avoid synchronous flushes to flash during Blackbox shutdown --- src/main/blackbox/blackbox_io.c | 5 ++--- src/main/io/flashfs.c | 8 ++++++-- src/main/io/flashfs.h | 2 +- src/main/io/serial_cli.c | 7 ++++++- src/main/main.c | 1 - 5 files changed, 15 insertions(+), 8 deletions(-) diff --git a/src/main/blackbox/blackbox_io.c b/src/main/blackbox/blackbox_io.c index f41c44982..d5eefc9c1 100644 --- a/src/main/blackbox/blackbox_io.c +++ b/src/main/blackbox/blackbox_io.c @@ -415,7 +415,7 @@ void blackboxDeviceFlush(void) break; #ifdef USE_FLASHFS case BLACKBOX_DEVICE_FLASH: - flashfsFlushSync(); + flashfsFlushAsync(); break; #endif } @@ -503,8 +503,7 @@ bool isBlackboxDeviceIdle(void) #ifdef USE_FLASHFS case BLACKBOX_DEVICE_FLASH: - flashfsFlushSync(); - return true; + return flashfsFlushAsync(); #endif default: diff --git a/src/main/io/flashfs.c b/src/main/io/flashfs.c index a4f8cefc3..e1de9fca6 100644 --- a/src/main/io/flashfs.c +++ b/src/main/io/flashfs.c @@ -295,12 +295,14 @@ static void flashfsAdvanceTailInBuffer(uint32_t delta) /** * If the flash is ready to accept writes, flush the buffer to it, otherwise schedule * a flush for later and return immediately. + * + * Returns true if all data in the buffer has been flushed to the device. */ -void flashfsFlushAsync() +bool flashfsFlushAsync() { if (flashfsBufferIsEmpty()) { shouldFlush = false; - return; // Nothing to flush + return true; // Nothing to flush } uint8_t const * buffers[2]; @@ -312,6 +314,8 @@ void flashfsFlushAsync() flashfsAdvanceTailInBuffer(bytesWritten); shouldFlush = !flashfsBufferIsEmpty(); + + return flashfsBufferIsEmpty(); } /** diff --git a/src/main/io/flashfs.h b/src/main/io/flashfs.h index 840f56044..4188b6f9d 100644 --- a/src/main/io/flashfs.h +++ b/src/main/io/flashfs.h @@ -43,7 +43,7 @@ void flashfsWrite(const uint8_t *data, unsigned int len, bool sync); int flashfsReadAbs(uint32_t offset, uint8_t *data, unsigned int len); -void flashfsFlushAsync(); +bool flashfsFlushAsync(); void flashfsFlushSync(); void flashfsInit(); diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 22d52baa3..561ce3e11 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -772,7 +772,12 @@ static void cliFlashErase(char *cmdline) printf("Erasing, please wait...\r\n"); flashfsEraseCompletely(); - printf("Erased flash chip.\r\n"); + + while (!flashfsIsReady()) { + delay(100); + } + + printf("Done.\r\n"); } static void cliFlashWrite(char *cmdline) diff --git a/src/main/main.c b/src/main/main.c index 9768f61f3..78068bef0 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -52,7 +52,6 @@ #include "io/serial.h" #include "io/flashfs.h" - #include "io/gps.h" #include "io/escservo.h" #include "io/rc_controls.h" From 892f1698d951e4459f224057df423cf5948b0554 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Mon, 16 Feb 2015 18:07:58 +1300 Subject: [PATCH 12/15] Rename flash_ident command to flash_info --- src/main/io/serial_cli.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 561ce3e11..152d8ea56 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -120,7 +120,7 @@ static void cliMixer(char *cmdline); #endif #ifdef USE_FLASHFS -static void cliFlashIdent(char *cmdline); +static void cliFlashInfo(char *cmdline); static void cliFlashErase(char *cmdline); static void cliFlashWrite(char *cmdline); static void cliFlashRead(char *cmdline); @@ -183,7 +183,7 @@ const clicmd_t cmdTable[] = { { "feature", "list or -val or val", cliFeature }, #ifdef USE_FLASHFS { "flash_erase", "erase flash chip", cliFlashErase }, - { "flash_ident", "get flash chip details", cliFlashIdent }, + { "flash_info", "get flash chip details", cliFlashInfo }, { "flash_read", "read text from the given address", cliFlashRead }, { "flash_write", "write text to the given address", cliFlashWrite }, #endif @@ -756,7 +756,7 @@ static void cliColor(char *cmdline) #ifdef USE_FLASHFS -static void cliFlashIdent(char *cmdline) +static void cliFlashInfo(char *cmdline) { const flashGeometry_t *layout = flashfsGetGeometry(); From 5f29eed017d6111a2eb156c321f8bb7cf45c232e Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Mon, 16 Feb 2015 22:20:53 +1300 Subject: [PATCH 13/15] Minor fix for flushing behaviour on dataflash --- src/main/blackbox/blackbox.c | 5 +++- src/main/blackbox/blackbox_io.c | 41 +++++++++++---------------------- src/main/blackbox/blackbox_io.h | 3 +-- src/main/drivers/flash_m25p16.c | 5 ++++ src/main/io/flashfs.c | 1 + 5 files changed, 25 insertions(+), 30 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index a0e357930..d47125821 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -644,6 +644,9 @@ void startBlackbox(void) } } +/** + * Begin Blackbox shutdown. + */ void finishBlackbox(void) { if (blackboxState == BLACKBOX_STATE_RUNNING) { @@ -1123,7 +1126,7 @@ void handleBlackbox(void) * * Don't wait longer than it could possibly take if something funky happens. */ - if (millis() > xmitState.u.startTime + 200 || isBlackboxDeviceIdle()) { + if (millis() > xmitState.u.startTime + 200 || blackboxDeviceFlush()) { blackboxDeviceClose(); blackboxSetState(BLACKBOX_STATE_STOPPED); } diff --git a/src/main/blackbox/blackbox_io.c b/src/main/blackbox/blackbox_io.c index d5eefc9c1..acaf0f4f8 100644 --- a/src/main/blackbox/blackbox_io.c +++ b/src/main/blackbox/blackbox_io.c @@ -405,19 +405,24 @@ void blackboxWriteTag8_8SVB(int32_t *values, int valueCount) } /** - * If there is data waiting to be written to the blackbox device, attempt to write that now. + * If there is data waiting to be written to the blackbox device, attempt to write (a portion of) that now. + * + * Returns true if all data has been flushed to the device. */ -void blackboxDeviceFlush(void) +bool blackboxDeviceFlush(void) { switch (masterConfig.blackbox_device) { case BLACKBOX_DEVICE_SERIAL: - //Presently a no-op on serial, as serial is continuously being drained out of its buffer - break; + //Nothing to speed up flushing on serial, as serial is continuously being drained out of its buffer + return isSerialTransmitBufferEmpty(blackboxPort); + #ifdef USE_FLASHFS case BLACKBOX_DEVICE_FLASH: - flashfsFlushAsync(); - break; + return flashfsFlushAsync(); #endif + + default: + return false; } } @@ -470,6 +475,9 @@ bool blackboxDeviceOpen(void) } } +/** + * Close the Blackbox logging device immediately without attempting to flush any remaining data. + */ void blackboxDeviceClose(void) { switch (masterConfig.blackbox_device) { @@ -487,27 +495,6 @@ void blackboxDeviceClose(void) mspAllocateSerialPorts(&masterConfig.serialConfig); } break; -#ifdef USE_FLASHFS - case BLACKBOX_DEVICE_FLASH: - flashfsFlushSync(); - break; -#endif - } -} - -bool isBlackboxDeviceIdle(void) -{ - switch (masterConfig.blackbox_device) { - case BLACKBOX_DEVICE_SERIAL: - return isSerialTransmitBufferEmpty(blackboxPort); - -#ifdef USE_FLASHFS - case BLACKBOX_DEVICE_FLASH: - return flashfsFlushAsync(); -#endif - - default: - return false; } } diff --git a/src/main/blackbox/blackbox_io.h b/src/main/blackbox/blackbox_io.h index 8fca16d72..62d590998 100644 --- a/src/main/blackbox/blackbox_io.h +++ b/src/main/blackbox/blackbox_io.h @@ -46,9 +46,8 @@ void blackboxWriteTag2_3S32(int32_t *values); void blackboxWriteTag8_4S16(int32_t *values); void blackboxWriteTag8_8SVB(int32_t *values, int valueCount); -void blackboxDeviceFlush(void); +bool blackboxDeviceFlush(void); bool blackboxDeviceOpen(void); void blackboxDeviceClose(void); -bool isBlackboxDeviceIdle(void); bool isBlackboxDeviceFull(void); diff --git a/src/main/drivers/flash_m25p16.c b/src/main/drivers/flash_m25p16.c index e977f257e..a6bd7b22f 100644 --- a/src/main/drivers/flash_m25p16.c +++ b/src/main/drivers/flash_m25p16.c @@ -278,6 +278,11 @@ int m25p16_readBytes(uint32_t address, uint8_t *buffer, int length) return length; } +/** + * Fetch information about the detected flash chip layout. + * + * Can be called before calling m25p16_init() (the result would have totalSize = 0). + */ const flashGeometry_t* m25p16_getGeometry() { return &geometry; diff --git a/src/main/io/flashfs.c b/src/main/io/flashfs.c index e1de9fca6..b271cec3e 100644 --- a/src/main/io/flashfs.c +++ b/src/main/io/flashfs.c @@ -555,6 +555,7 @@ bool flashfsIsEOF() { */ void flashfsInit() { + // If we have a flash chip present at all if (flashfsGetSize() > 0) { // Start the file pointer off at the beginning of free space so caller can start writing immediately flashfsSeekAbs(flashfsIdentifyStartOfFreeSpace()); From f21f5d51b43c0c778934c2966186dd2c290a9684 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Mon, 16 Feb 2015 23:35:28 +1300 Subject: [PATCH 14/15] Document Blackbox dataflash mode --- docs/Blackbox.md | 162 ++++++++++++++---------- docs/Screenshots/blackbox-dataflash.png | Bin 0 -> 54161 bytes 2 files changed, 98 insertions(+), 64 deletions(-) create mode 100644 docs/Screenshots/blackbox-dataflash.png diff --git a/docs/Blackbox.md b/docs/Blackbox.md index 05effe956..d90faa5c8 100644 --- a/docs/Blackbox.md +++ b/docs/Blackbox.md @@ -5,7 +5,7 @@ ## Introduction This feature transmits your flight data information on every control loop iteration over a serial port to an external -logging device to be recorded. +logging device to be recorded, or to a dataflash chip which is present on some flight controllers. After your flight, you can process the resulting logs on your computer to either turn them into CSV (comma-separated values) or render your flight log as a video using the tools `blackbox_decode` and `blackbox_render`. Those tools can be @@ -21,20 +21,17 @@ https://github.com/cleanflight/blackbox-log-viewer The blackbox records flight data on every iteration of the flight control loop. It records the current time in microseconds, P, I and D corrections for each axis, your RC command stick positions (after applying expo curves), gyroscope data, accelerometer data (after your configured low-pass filtering), barometer readings, 3-axis magnetometer -readings, raw VBAT measurements, and the command being sent to each motor speed controller. This is all stored without -any approximation or loss of precision, so even quite subtle problems should be detectable from the fight data log. +readings, raw VBAT and current measurements, and the command being sent to each motor speed controller. This is all +stored without any approximation or loss of precision, so even quite subtle problems should be detectable from the fight +data log. -Currently, the blackbox attempts to log GPS data whenever new GPS data is available, but this has not been tested yet. -The CSV decoder and video renderer do not yet show any of the GPS data (though this will be added). If you have a working -GPS, please send in your logs so I can get the decoding implemented. - -The data rate for my quadcopter using a looptime of 2400 is about 10.25kB/s. This allows about 18 days of flight logs -to fit on a 16GB MicroSD card, which ought to be enough for anybody :). +GPS data is logged whenever new GPS data is available. Although the CSV decoder will decode this data, the video +renderer does not yet show any of the GPS information (this will be added later). ## Supported configurations -The maximum data rate for the flight log is fairly restricted, so anything that increases the load can cause the flight -log to drop frames and contain errors. +The maximum data rate that can be recorded to the flight log is fairly restricted, so anything that increases the load +can cause the flight log to drop frames and contain errors. The Blackbox was developed and tested on a quadcopter. It has also been tested on a tricopter. It should work on hexacopters or octocopters, but as they transmit more information to the flight log (due to having more motors), the @@ -49,10 +46,11 @@ details. ## Hardware -The blackbox software is designed to be used with an [OpenLog serial data logger][] and a microSDHC card. You need a -little prep to get the OpenLog ready for use, so here are the details: +There are two options for storing your flight logs. You can either transmit the log data over a serial port to an +external logging device like the [OpenLog serial data logger][] to be recorded to a microSDHC card, or if you have a +compatible flight controller you can store the logs on the onboard dataflash storage instead. -### Firmware +### OpenLog serial data logger The OpenLog ships with standard OpenLog 3 firmware installed. However, in order to reduce the number of dropped frames, it should be reflashed with the [OpenLog Light firmware][] or the special [OpenLog Blackbox firmware][] . The Blackbox @@ -66,18 +64,18 @@ along with instructions for installing it onto your OpenLog. [OpenLog Light firmware]: https://github.com/sparkfun/OpenLog/tree/master/firmware/OpenLog_v3_Light [OpenLog Blackbox firmware]: https://github.com/cleanflight/blackbox-firmware -### microSDHC +#### microSDHC Your choice of microSDHC card is very important to the performance of the system. The OpenLog relies on being able to make many small writes to the card with minimal delay, which not every card is good at. A faster SD-card speed rating is not a guarantee of better performance. -#### microSDHC cards known to have poor performance +##### microSDHC cards known to have poor performance - Generic 4GB Class 4 microSDHC card - the rate of missing frames is about 1%, and is concentrated around the most interesting parts of the log! -#### microSDHC cards known to have good performance +##### microSDHC cards known to have good performance - Transcend 16GB Class 10 UHS-I microSDHC (typical error rate < 0.1%) - Sandisk Extreme 16GB Class 10 UHS-I microSDHC (typical error rate < 0.1%) @@ -87,7 +85,7 @@ the best chance of writing at high speed. You must format it with either FAT, or [SD Association's special formatting tool]: https://www.sdcard.org/downloads/formatter_4/ -### OpenLog configuration +#### OpenLog configuration This section applies only if you are using the OpenLog or OpenLog Light original firmware on the OpenLog. If you flashed it with the special OpenLog Blackbox firmware, you don't need to configure it further. @@ -105,42 +103,16 @@ of the MicroSD card: baud,escape,esc#,mode,verb,echo,ignoreRX ``` -## Enabling this feature (CLI) +#### Serial port -Enable the Blackbox feature by typing in `feature BLACKBOX` and pressing enter. You also need to assign the Blackbox to -one of [your serial ports][] . A 115200 baud port is required (such as serial_port_1 on the Naze32, the two-pin Tx/Rx -header in the center of the board). - -For example, use `set serial_port_1_scenario=11` to switch the main serial port to MSP, CLI, Blackbox and GPS Passthrough. - -Enter `save`. Your configuration should be saved and the flight controller will reboot. You're ready to go! - -[your serial ports]: https://github.com/cleanflight/cleanflight/blob/master/docs/Serial.md -[Cleanflight Configurator]: https://chrome.google.com/webstore/detail/cleanflight-configurator/enacoimjcgeinfnnnpajinjgmkahmfgb?hl=en - -## Configuring this feature - -The Blackbox currently provides two settings (`blackbox_rate_num` and `blackbox_rate_denom`) that allow you to control -the rate at which data is logged. These two together form a fraction (`blackbox_rate_num / blackbox_rate_denom`) which -decides what portion of the flight controller's control loop iterations should be logged. The default is 1/1 which logs -every iteration. - -If you are using a short looptime like 2000 or faster, or you're using a slower MicroSD card, you will need to reduce -this rate to reduce the number of corrupted logged frames. A rate of 1/2 is likely to work for most craft. - -You can change these settings by entering the CLI tab in the Cleanflight Configurator and using the `set` command, like so: - -``` -set blackbox_rate_num = 1 -set blackbox_rate_denom = 2 -``` - -### Serial port +A 115200 baud serial port is required to connect the OpenLog to your flight controller (such as serial_port_1 on the +Naze32, the two-pin Tx/Rx header in the center of the board). The Blackbox can not be used with softserial ports as they +are too slow. Connect the "TX" pin of the serial port you've chosen to the OpenLog's "RXI" pin. Don't connect the serial port's RX pin to the OpenLog. -### Protection +#### Protection The OpenLog can be wrapped in black electrical tape or heat-shrink in order to insulate it from conductive frames (like carbon fiber), but this makes its status LEDs impossible to see. I recommend wrapping it with some clear heatshrink @@ -148,30 +120,92 @@ tubing instead. ![OpenLog installed](Wiring/blackbox-installation-1.jpg "OpenLog installed with double-sided tape, SDCard slot pointing outward") +### Onboard dataflash storage +The full version of the Naze32 has an onboard "m25p16" 2 megayte dataflash storage chip which can be used to store +flight logs instead of using an OpenLog. This is the small chip at the base of the Naze32's direction arrow. +This chip is not present on the "Acro" version of the Naze32. + +## Enabling the Blackbox (CLI) +In the [Cleanflight Configurator][] , enter the CLI tab. Enable the Blackbox feature by typing in `feature BLACKBOX` and +pressing enter. Now choose the device that you want to log to: + +### OpenLog serial data logger +Enter `set blackbox_device=0` to switch to logging to a serial port (this is the default). + +You then need to let Cleanflight know which of [your serial ports][] you connected the Blackbox to. A 115200 baud port +is required (such as serial_port_1 on the Naze32, the two-pin Tx/Rx header in the center of the board). + +For example, use `set serial_port_1_scenario=11` to switch the main serial port to MSP, CLI, Blackbox and GPS Passthrough. + +### Onboard dataflash +Enter `set blackbox_device=1` to switch to logging to an onboard dataflash chip, if your flight controller has one. + +[your serial ports]: https://github.com/cleanflight/cleanflight/blob/master/docs/Serial.md +[Cleanflight Configurator]: https://chrome.google.com/webstore/detail/cleanflight-configurator/enacoimjcgeinfnnnpajinjgmkahmfgb?hl=en + +## Configuring the Blackbox + +The Blackbox currently provides two settings (`blackbox_rate_num` and `blackbox_rate_denom`) that allow you to control +the rate at which data is logged. These two together form a fraction (`blackbox_rate_num / blackbox_rate_denom`) which +decides what portion of the flight controller's control loop iterations should be logged. The default is 1/1 which logs +every iteration. + +If you are using a short looptime like 2000 or faster, or you're using a slower MicroSD card, you will need to reduce +this rate to reduce the number of corrupted logged frames that `blackbox_decode` complains about. A rate of 1/2 is likely +to work for most craft. + +You can change these settings by entering the CLI tab in the [Cleanflight Configurator][] and using the `set` command, like so: + +``` +set blackbox_rate_num = 1 +set blackbox_rate_denom = 2 +``` + +The data rate for my quadcopter using a looptime of 2400 and a rate of 1/1 is about 10.25kB/s. This allows about 18 +days of flight logs to fit on my OpenLog's 16GB MicroSD card, which ought to be enough for anybody :). + +If you're logging to an onboard dataflash chip instead of an OpenLog, be aware that the 2MB of storage space it offers +is pretty small. At the default 1/1 logging rate, and a 2400 looptime, this is only enough for about 3 minutes of +flight. This could be long enough for you to investigate some flying problem with your craft, but you may want to reduce +the logging rate in order to extend your recording time. + +To maximize your recording time, you could drop the rate way down to 1/32 (the smallest possible rate) which would +result in a logging rate of about 10-20Hz and about 650 bytes/second of data. At that logging rate, the 2MB flash chip +can store around 50 minutes of flight data, though the level of detail is severely reduced and you could not diagnose +flight problems like vibration or PID setting issues. + ## Usage -The Blackbox starts recording data as soon as you arm your craft, and stops when you disarm. Each time the OpenLog is -power-cycled, it begins a fresh new log file. If you arm and disarm several times without cycling the power (recording -several flights), those logs will be combined together into one file. The command line tools will ask you to pick which -one of these flights you want to display/decode. +The Blackbox starts recording data as soon as you arm your craft, and stops when you disarm. -If your craft has a buzzer attached, a short beep will be played when you arm. You can later use this beep to -synchronize your recorded flight video with the rendered flight data log (the beep is shown as a blue line in the flight -data log, which you can sync against the beep in your recorded audio track). +If your craft has a buzzer attached, a short beep will be played when you arm and recording begins. You can later use +this beep to synchronize your recorded flight video with the rendered flight data log (the beep is shown as a blue line +in the flight data log, which you can sync against the beep in your recorded audio track). -The OpenLog requires a couple of seconds of delay after connecting the battery before it's ready to record, so don't -arm your craft immediately after connecting the battery (you'll probably be waiting for the flight controller to become -ready during that time anyway!) +You should wait a few seconds after disarming your craft to allow the Blackbox to finish saving its data. -You should also wait a few seconds after disarming the quad to allow the OpenLog to finish saving its data. +### Usage - OpenLog +Each time the OpenLog is power-cycled, it begins a fresh new log file. If you arm and disarm several times without +cycling the power (recording several flights), those logs will be combined together into one file. The command line +tools will ask you to pick which one of these flights you want to display/decode. Don't insert or remove the SD card while the OpenLog is powered up. +### Usage - Dataflash chip +After your flights, you can use the [Cleanflight Configurator][] to download the contents of the dataflash to your +computer. Go to the "dataflash" tab and click the "save flash to file..." button. Saving the log can take 2 or 3 +minutes. + +![Dataflash tab in Configurator](Screenshots/blackbox-dataflash.png) + +After downloading the log, be sure to erase the chip to make it ready for reuse by clicking the "erase flash" button. +If you try to start recording a new flight when the dataflash is already full, the Blackbox will not make its regular +arming beep and nothing will be recorded. + ## Converting logs to CSV or PNG -After your flights, you'll have a series of files labeled "LOG00001.TXT" etc. on the microSD card. You'll need to -decode these with the `blackbox_decode` tool to create a CSV (comma-separated values) file for analysis, or render them -into a series of PNG frames with `blackbox_render` tool, which you could then convert into a video using another -software package. +After your flights, you'll have a series of flight log files with a .TXT extension. You'll need to decode these with +the `blackbox_decode` tool to create CSV (comma-separated values) files for analysis, or render them into a series of PNG +frames with `blackbox_render` tool, which you could then convert into a video using another software package. You'll find those tools along with instructions for using them in this repository: diff --git a/docs/Screenshots/blackbox-dataflash.png b/docs/Screenshots/blackbox-dataflash.png new file mode 100644 index 0000000000000000000000000000000000000000..1f891c0c57952d09ee7700b0968a70972adf2bee GIT binary patch literal 54161 zcmW(6Wk4Lga*x9u3KWWKaVzeH;_jum6_?^J#R`<-?(XjH?(Xh-xXa^v`zP6KvNM^? zWHORq1vzmP#7~F-0H8=pd{Y7d==UlV2p;@iY{>I7z8827qTd~qZGJj9>)ROvUyW=G zj7cP|^i7PFjP;FNe+?S*0RR|KkWmqJadF(;S(%?1*eEaC+}y0KE^ZomD=p4WOpH5h z1b}2z-`{sV;$L1XU~2kvY@{bAC%3=1L0w&~ zpy9Blwtv1xT3lT0WgN)NOiCV2Ir(WYGu7MI*T=!ZF*!MTa2ytT1tsti4-`_8) z@?Kq@Zm27Jd%J6>uWIet9vtZM?e+f?>EYoK z^Ih&c`=>3#b%Vp>tD9ZR%hOwv^@oQS5fLH%gX2e#^S8IR;o;$p)rq(Jx2np*-QCUN zilDT#w4JT>xuq=&3$vb{_Ntz@mfFUpk@~ExOf4-i?pd5KARzE+=Xk1$tEuswG1GyZexFYaea4p_w@8MI5^nW#$tAM{+;|c5AQR||M>Ca z+uL(_d3kMZZDC;{3kwSw85t8J^X~rc{{GI}^V`Yc$^PyxJv}`U5m9qmf5)31Q63n`qw_H2^UAA;{zIL_&%nIWR9ZhFVj% zSBLly{37px_g{_Modu1$O0 zZ=U4;0bZp;quNLGD7|5!aW_02&nP*idlJ0J!H<2r58GYWXnW=r^tye}?Vt9lb{xI) zg5Plus`GLw6ZmheHXT}?AT+Q+z+`L#tOi|H*A9;NN6D$YZeK#qtDf;=$NQ$nthB)~ z#6xIkmM^1?{uC6X&ZQpLw9q~R)Ncd{9g0HRbRq;avNeSUIH9VIuOsK#i3$c&~?uL!d=5*d8(01We zGBA!N`v{=6q^8`Xeu#=_{s>s_BCu-ewxT`f3bLDlN<3%@saE4(Z#k*NL9cP+w^Q4V z(ZKo2_=9C|dynoGr0khD840u@Ks~S1SnI@xO7apvZ(!E$VMqXYJ>N>-_3m8k8~g$U zpEoo6`=>FZBK%hZ?EK(-ELdE72}7Z^9){Il`O_SZ;=Mm?1MS|2xh_++f_$%9^q97z z+lTpOl>f1mMeb`R!Ph;_e1pq9rt~3in_c%Pbsd8@TXQY1hbh6g*Sq$&pm-e~cAD^Z zZD-Tbq&Kf;_5A+>>z#rFGQOY!Hm{p#-uJu8^87c$f-=LG@7*8M+f#~O^Sy40mBYcV zyqRzB%cTwg9If0m-mh1sg6-VeUND$m?Bs{)?T?VR*Q>uh|L2)R3Sz-8gn%_jL#9)g zvPSS-tjvK9&338(q{%U+4UO%$Q}a98?_#6KTr5VCQ}rJv9)zN=@2b?;OZfe*Je%Th z8WV_kXDNV0Q1He+e$dI|(a|d~>}5zIfac~bGUR#uB>$yKT0qu2iL=zBodT)tCm>W* z+kb5JwDQ_w72r15BX53+SN4iUTUu5+9Iox4wv8sB{ZRT!2M2O(f4hBaurOK-zv{Dz zgY&BFsfriqd}wR05sq(bpW*Pdzqqu%8nW>sqeC2)>>xLey7M6&av6xl(5atG(IWE#uL9LmlFWb?Sikj^>6d5WZrMv z-hVhXFGJhk=B6liHKpU*-v*)OFjhlKQSMzs@*_{^l~di>aLQ%v9AEq+eka~IUsxC0NWqXVz=m(8MW zFWV^>j3?e67PC`3OvQ1G>yJ;A#&1uQ^@p#y10hd>k(ORNk%=$uUW>1B74&5G9K*{( zx`{bVJ0KGFVv^R^E1iD@0xusuoKtme*TdvXr$DmgGb)m|`6z%gZbyTaW4t@;>!vl7 z4-K;3AP}K+i2!VTmInLeZuS;M#pHrIM&+S_-0+c>uXllDgi0D*1WrrHRgj_2pp5;I zoY(YH`JkgkPVMR`xHF+Y*Y^A4>C$rYWyI^doO&h#ign@gNjj{pua*R$v1=dLJSU4W zS)#wODNzv~jB!}SS1XO&?1E`eqtfXp;QRY~|5w4q6uhV6u^(7a9+JPHn0;(KsD_%{ zZl80&X)+DVq zB>bLwsK7)|MK+TsZWAY^GXOB}ynO-^u0c5hiG_oHc6|NGtkxQ*@g`xK8rQGSC53A0 zQ?Dv|E~Dk48V~Nf8oF%Y@1w)I`H<(^&2HYG!*w3ZmWLm5^V5ht##+nK`*)i6E-AFAg;oM(r_5;ylqSdW;0++j^ zV}CM=XlHR)gg!q*12w&lm`-g_Hs0%D_OfeN7q7f=DU8$v2g!4>XepB@w?}pyxd_%@ zQO=rweLXjSd7$I*75X?7s>(^yVvD--VTbCYoJPof6Jw(K!($2uJTT0*y)W>TQBf_} z2J4;<96;s!qBCl#HD+PmhT0bPje@zDoV&DGa^kvTo&ib%+bfD!ViTZ<^2~N-;zzpg)a^KpNV_d#m#E z{S{>4e91yyrra=QtG(B%(A^>&5An?e9F!eN^n~r9Di#DU%teEZrcIe)pdTRaM_G&*5xR;09KiUua zeSADa!W+vECjPy8`LJ!E+1ck+elInKr%j!g_c9KD6g{qsp-YD>dwu!BZJ@c=hYL0h zW%2nHopE2&Xuln%c}m!NH)}&b#HHh6Y}iaXYACUci@6g3{SuE1qa(6OPms|jAo6KT z6C3Q~5&XHV!Q!91T``U{3BYd_gatitmuX*PpzE4 zK6B;)FEs8;j6SATTJzlE(EU1JU<2+4Rl)?+?9q)}E*4x?ol^{G!3!F8JBxne`q5OE zWl4$cIS)Tu$oH`ywyVO`*OZ;cm#R3=XqH{BwyW;c1m1>Xx<3FN-j8V9ALW!NRL|Jp#&8B<|EBN(3ZHUUz$&V7wvZ58iWmyBp$IW4T~j1u|J31IDt6H> z21$425sXf!*b#-K>t0qMBZQa8@6iRZ4dS*{+mC7k&H-BDAWIcU*W*Fyfamp* z)j1%sTDuvHQe58}C{Ve{Jn+<0wj1&<{poKLz(^ko z@Y$@O%e%?gBitA;R0eH)ju!ACmN~VWpSJ`x)tU^q@$)*D2{w2QKYCJ9iWlcOw@>4B zj4{NH6TuucEfPuI4)Hc`(j+{-B*WTQFU<%TlxVI7?!ArQ+zZf?OZr)=;cWhvej z32;7->h4#MJ=`|hN7R@)%vwtceAvJm-R{t#XJa9NCiP6Lib*q->zXS#SL38i-w9)i(j+Nha-oo;lf|`+oX(&>PF8&eD1cxkx{8| z;RO6Y+FutcJ!3WNRIIsOjK<@1<4cl4K`9H)mM@Qwo~o2jw>DpCrEduem(*PitYH;g zZO0$qe&}BI`@zwLLxm`5I9AxLw~=e+u@!z}Q*9Sy45hPN9DTBh^L+MRTj$FbN&g8| zLci_#+lQs);>~JJOYQdJYJ9!@a%CudctdV+NW&A*xWx9;(D*4DvNBhdN(?(9C%YL0 z3IYK}vibo2vb+uLiL7_NjzR+Y7=4>{gVRf5b<=NWe^H2w`xD1as-)oRgQ8o(hKHTo zOCN!LAnEoA9udHS^T{J1@OG|i&BTBFpe+204>ABGt+l`%e@^uwwsN!m(9RnT62c*c z9$=05_;}S(IFjP)bRlAMW3sd)DD@$Q$6G4mR%Y)3v>8zCeB}M;s$k;%CZ6HVYC4lfteJ6~trLJjcD^D6koWS+2yyZK3BbhY|Wb;GeOEm%T;mk`i7P>8Wnm%LUFU@}56=0u}3>&E!T0AFW?#?FBM zLB;p>1SM!t(f7@_LM|1;WQCN|@T06Q4CO4I+A=Vcfx8LdKI6>HY5YThHfI$bN>cKvO zs7r!pix}YQV=N2lX}GIQJa^MnpL`hF_Xi$R z?U@1F5~JD3o8o^2{%ZU+Pj@Or@15#xq+eE$H#m>$33y?3CRAN2?8X&+nBd;HIKc&i zY8nXNg(L^lvTurSQ>kgVVNZNLr#+Bqlv`bGQlQOS?RG~;jp^p|;#akhuDPtY`>_R$ zlX~C8G!~aFYy`Z~7TmlUChkWgxO|l8IKzwIMiY@qRIQcqdgSu06n@SHSS^nt>Z@WB z!?W?Ff>L-tQ@i8~DG1sMWN-YHyZ>9k&&_b%tZ>Qw^@6u;ViA8|?k0c_jVcK7@riR! zOR(K+`}Gk2PmtZ?b^4}r z8L_1fdI5k4032}#5K^0d9nJKGPw|eW2r@9PHC)I*M3UtW?b0x;S6p7YECqZ<{+h5Z zWv*|c5(}X~`=EhoF!HJfJ%JJ*)??! z%NLjKuIC&SZYM=-THW`lI|z|UV*hDbRc0<0st2e(R$_M*KU`vH&#qyKhFVfYmBNF7 z2nj5b+z0cJ5`@9F;ivWmMW7%gNL>Vb6~H1sIf3$g zIht)zZTB?+c!j)CWp3tCv$wSc0r-qb{EQ-DLn3N^`sO4!pzU9`e8#YPI}R8~fTjcY z`sQNXJ$LfkUh}pX0u_G}{Cwrtn7a|U=)m7q9S!!2iVVf;VhDU68{05#q2MM?h8XNw zd{Q<4`TTp>NF(>@*aU>&Ya{VL85lIIlYpPZEeH*1SXD8O_@c&eOhT@ zZ9E~$xVbBr(Rp~5)%$AM_MmI*?P0#Vv~MGa|2bg`98oXX-NF@+DN)BEqS(ZVgLr}+ zBX6EjW@i?Rg#{b#6A&4)uDOB zm`v>45J8&DnffDcC;NhsP1u?=2R(@{;98PypOBNnZt#A;lCAnLp=!lT!IaO9cLHT1 zz`%#+O>&`U&WE1EuFfY8s`Tda`YVQXuEy$mrpD}-XUk1Nj^xq`ZyaJ^8~`%cQ9v6V zN#c+7JYHAn8R~-P-WGEphYgV4YMy;F+6x`v^9cYxqn7a6ZmcFfu7}CNL9PiKT zx|{FG!!LfI@SG4X=YarSIKZbn8mRCcZ}Kw%wp-GJQg?%#3HQRFBbvYp;P0z}v-W?X zWbQx&(B`%Fv&3j;E9%}SBsTrTr<&|wAn#q56_4?2ss@l~(vkvP=m$atD@saARYx1u z?}nqHrqkJS)s^0?TL=Cvfo8Z5s;2-fFotT*4<}c-yQr%AWPmUYkn{n4vp4(&BX{jD zYfDwNoS$7@_YwhS6zH^e(5esJ+XpNVvfk<7-Pft1(P>24E6@OCV1;sp_9rJs-lbcc zC~u9pBtaCQ53i$-EW;O^8i?$hxxtWmU-SKYd!=^LonnEfpV8jqEHF7hs~5J3_e@yA**JOt9n)QahjQW&dj2Pp#>&C3I-8VHxQaX~ z*Rb3?Skt>a_MkK!=Ywvv^-?(Vw}EN-_WJ=)e>>3+buf^z$H@YFUT!frOQ2DGHZg7C z1-|4%L58v$&D6l{aQLtRQz`ZO+fLy|C?lKJ&thzENhbofy2z+#hCJ`ZZ2;wjGoJTuR^5Rp%2}{Z&qk=k9ckpA?rL8{P#*W9QZ+Y_u1`C1()~c^b0C*xyD>$j zDlg&%jrP}hRT5WzX3*X>=-j2setq(WM6iJPxm-|aTwLhstfGQ}J$a|QBvCOWxZmu`o=J`D>5@}LQA z2%do;bcVY&YlmQoSpS?VTQODDIvFbV913H}od=C+AcJQNIAU+S8T8~FySEc)aLm>r z=TTmtcV_s^-FQCJxYPE?raQK1@A+x+0!@x`zePjv+;gp^KCW}uJXwymLtVY^ByUa5+KWNW^I9Gsja(nsL^O3hj!TnP;RHM`deuz7 zv_uO;gK{{$Y}?-WVqSL)Jk8rERE=Fo9la4hk8G5|{_bi;981Jh3xiP?Qc7=fj=)#6 zB`idYB}-^^hGzDOoWh!A%@K`V-%}6Z{;I@(%+nlmrr*UqM|s1jFzlzuZ=o zhlh`~a*P2AUf+nX=eCgnw_A>LN%`~TX1zC}a_}wWgMbf8aewqSaGrWU@$QqsHyG=( z0ysE&qMS=~7T^HvH(a&`bycF(K`_945-w}sAZr3VxeVE!P*bbBT8_7o_x~$d2iN^0 zSW)8U1pDxFIdJ`M@;%W|b=+C}pnAm&w4Grtuo|h(DoVh0?4>P=fvo$2KtpNXZGVYj z0LlH~G^S*Mk-N1S{f<}?`$haak#OC`(NR9|0`gQEZE`XwM`{FQ;vzcxN?%RCHNGHd z%nv9c1LoVmfWu0z4c}K^Pz6XpZ--G~-q)U)1H!kkuMGDXHGb7Uo(_?Q_zf{L+xjsH z0C$gYV|)DeFON4!y__A^Z!+cDx+y3t1BbtX2`)T@1h2So+!Me2&GEkUtT(L^8UXw8 zDc|LTNpUr#?Y9{+2}dFm5kkY+M5d$dRYxXx;{_f0>VcFGUZ;7RDZ=BR<1CmD4)ru` z5V)-VG``cDa}P>LsNDhqsD+F2L((GaR!?VZ5RO`k+@J7qr{Qo2d2Gfx19v~!J7e}B zQkTiZ6PzZJM5bd)*&4#-1E$d)k;r-vm)*;Cgli!2mw21yS}Qn$oNYlg z$Wo=@GODe^!=+W_$Mnr}yM!jNN7rvX!{z(if8EPeM?Se7j5eo!;e$JbANE)J)E#jN z_P2wb&YN54``~~XtCzSN$_%6+5``+bsOKBFyAeXTihK&3+xlu~EU;_+$!77w7aNKV zmrT{-y7N6@gp=j{f6yz+RVMNX1SwkM`vGClyH0BuaLlUe>SfRrBzf(e^JQAD_CGq- zuZ1#_>C}Z?8Xj~!8qjexpVsz*FRR~;s<*0D0*(VpQa!kmd+VcAAfw&xOgZi73$XKC z^5O5)Ht22e#>}yT=8?|R)BELNOEu*sNV+in!m?wg1j5nP{<(cvzJ6>d=vRkE;S*)y z)7|i$RMk#j>qFEFQ;(#Yn%C6pi@U!6Ig+HtgGWgOg`Yx017Q8CPPo zazg%qzZ)f*3HX$>x}&frE>cAg5-H^UTm=CSg=^bj&vb}UN1HENOQo&@*S<3E-Qo@u zkqQ-VhY1Tl^ILJH%!D>O{`u$k6JD_C>J9Hl-j5sQsVEKAM(dNF$Ih?p)gbj?f$&8i zWn3Q$aspKF4H}q8Xn!0EP*WT$_DnC%*>@?eyaB3OOwOJhj%3DOMCmyoUlLFf;=iM9 z3|A6$ptaSW8@1sbgHE(~fM?^^M87X`^*f6`>B9~iqv0}KWjlT$r@3PldI2Ma@#9@U zl~Sp8Kzg}HJ00Das8Y4LU@9#WHjYC-bMKMs{dDYzpy#d{G!!z)?y_^Jj6Se#^Ex=y za~GdZukmW zZpi}wF_hJKQAPQSBqS6B42uY4cKa*FwzU$=8f61$;0{l7hBU6emDsX`hQ@|BaBiKf(PeA zzlKeXN8Az!%d@h{;8-zeAGF|P?xD*XE#HIM31hN?dQ0!aL*bVt1k`@k3(cs+p!d*c zIeqNFQ2KK+B2c(W#uOpF+O5u(B;AW0kYt_i+>k%atEIKzlB=e&GC*w8vU7uTi=|_B zjbdRwjp*6EcF5|1kcT|)o~}v)*s&v)4k5+ z>%EcIf<(O^rv+bDZGyac=`UaBj$8Sk{ob3<0&U(7}EDv>SAoEY7Le=jHnS8TW;v-ko&d3$XJ7!fPn3Kry+hL$_=Kt{# z)kVBK=vV5@1-fjAaeb7WKbG0%grvgly493s1*&k464vq;F4DBZV+5qrQv+q|@6M|u zfur+9FY`7*rR{A*WqOBNkGqaGZ+FAtbGv2k_nYFxuMkHx!AH9^qt)(XomWV`vtZNN zMU%MhSnd1w-FP}8FNf9TXe$TxgOL!H{EfJOybOxpko9MGi2~&$gxemYoR60Z5gMJe zV%P&fHD>79EaoV7h9X+-NS_c;HHMofrUE?@1-W*tn2VWv{^)&89@am%?~J?rD!0eE zoiU<vtp^>r-FqWiHBSx7_=cg)_m|>Gf zwR$er@=-9|xSj#3zx~F~%KG5wE1318(5;mgskFp4+&(!=@TgBHM#qLFNhM24WtrgF z;wV75Gh$0WPOha3Jg+>Je-L~*w1>Q9QMNCc>pxkPM$U;w>7nLN0m{Ul|hoO{y#@%ue`_-Uw>R-v+3NaK0U*r1Qm3U6a-OZRFvq^0x!=&x<+p-q(-EHqH4p7%K3L2>OJI za2Xa)@mH6>uFRdiNCbfTp;YBuaV9QCbsbK-KKae7|J|zS(NuE9%DacdAF#ttwZeO z%VSCUmWBTo5uWj)RyM@xnam8b`gAEA6?C%}U-}_AY>CfmxV?3hnvX2!fU{s}09fR&A?rW{>E=(0(237Khl(}QZs`lyv(vb8>%NxdHmD3r(AUw4&I@~FB7^Po-6vHSfUu-|qilrfWlG;BwR zu4#Og5ywE5&eD(~rX4jlnck*W)Rzk3i7QE>=NHF-?Ob)|Z2!=+e=>GjBCm;jH5#AcaOD}@CU`n0gD0Pav@{<8) z0&3*CQ@e@FbVT72?+AmVqKZ#7`ica zAX}m$UhoWdEJu(+CJy=!;eMFXY`gX_OX1|~>G2G!ec`USlbA{|i%|cNp%D%?|;pXgYO8(_H$+tly2&yqF z=&y~LPEi?-6Xedy_bEmHgj_vwk*iuvnDe95q56BxA`{Ma-SuBp_?H-5D;m+{KcuRm z+yxL^1nfy@IlPIu2-yL=CKZfQJZwNM@)SaCb!%UBTTwI@I3*mQMyp1fa;=9xooPtO z<|}HPnCn*Z;tu821x!%j)>7R zm8}}H)+j#{$mD{cP>@PZ2T*Z^!$UsAX~x8e{6)+{2e`VOw7=kO@|?P8sf&M6cs@=I^Y-Vw)LUj6r0}{@A*zw_zuFKWnbcC5Q&li!IUMnNR;RRqJ z81ZOH1!DU7&-E$;uMdE@2k)U)vxBO(n4nw|BlpV}G& zC>{zRS-|aG`7_n=1rWp8QBWy@1<;LI0+|iOev>`_o*UR;HvI$7LE)x|@pEYSxUXqs z?=rM2L&qsIR!OTueWo*k0!JMU&JX~cwD3$TmdDV(VeXQ$6=b%tIRkwoj0ho7dO)Rq zhhki)0>wW?35vg58wvOT(A6b|uee!&U#)Bn54bs|wri($VwOVmMYp30JB@=iU2t*xyu5PG6v_fx?Cc$KSL>s&2IGz^Ft;!kAxhqmIwS z@v!^n#}et^Z@EzV6P8Ya7H}xp=VLpdjG0|E2PsBpMMK#o)7o}5grIoS z$wT2dgghHUq&{x^*aU^1_~(ZuQEq=yuUFx;S#_ZFY>Dx;5oVuKEp6Fi0I4E0;4|#Y z%*xiCG-ViO`_YaO8z=cSH6mX-IHcP_;e&+)x#^!O{sEYx!%D3DjtvmQb0@K& zI)?64q?&JlyI>L%WaI=j%@c$!pn~45WfgxIDlF$!sYR*U?IU0uLz3kolxi0+R78=* z2ROh5lrn0-H!mF)HEVtTOY$Qnx5+PcS1Nw`&@S<}fM!q z;iMD{-E#uruR<#&a{_=&l<^bLG0S+GP}b5y_?@QFE)8_e0T<0^5MnH61~y}YAUHId ziyxd~92pP*fgT+Bp)*b2VT9-eIQ}^9&?;z@4X;jSi@;>#Ksjg4mTj9QA~I%w-?@5V zMe?3sbp5G8LT`@^(~sZPRKSs6M5koM(J-X^%s-Z==$u3O35}y`*n+#gXLsQ2oP?3E zs7h?GuahhgF;mO^A>IUc!mf8aS(Y!p0vb+&89*jq#3*YjQ^rJ`98Jk=nOrZ6mF_`o zU0M5!I7`2&hAhVN0OQSDxQ{$(Sp&lZVi1Gv#)GxBpr=K4O4lnSYIp2a?HR$wQy?ui zXM(8RsMrgmSQ!oc(Os|R??I5vUq4`LAiyBRK9OiDy=slv(W98c<{PIOLB#8~DwRzcI}dJaz_4tbJW19=fQLmTQ4i?gnJZ?bQ%R}7Y8@H;uFmk| zhjmy1W3hGfh`tc;hay%#CgKs?`S+4c4&y}h=L*Nr2?qaf(p5wY6aSuETE8p=b++as ztYNRyoi3`VTsFk^bs1DU+BepC<$S7?-+}0yRoZH@qP%{za`OsUb4$o50_{?{tcR9- zfI{6@3Oj9va3d)!t86ioiSml36xu)l(5qlKvi0iy9^T}Kzm4n|`9pm>0UNX94qq_UY0|P=kAXqw;tKp)ZsZlVuQG4V+!0Sycdc*cvWs{Jo z8c8yi$%OjV{hNC>J#hoFfR!7A3=EwSYLoAlS)^iBaz;u9QCiT4mz9cbRFY+paXoEN z2)faV)=}Ho*z|)24a*dj1G0rA8kf0^VEUT9ki0p#`!Fgi;d}pgO~?$a^@wLMa|tU# z5C1^t!b5`}i>mZ>=K2*5jR2jJBd&3lg7T-sl$f9sw})|Kr1P8sljXPPimZai0P?X9 zyQUnqWE>^Jy&Znx2WT_>2Msq8;=w4?2suU6ISgJJ84|pVM=@m31H9CsLYczE^LetL zgQk$$)B&uO0El(td657Mf%f+<#w&c+Ir|1YMmh=f5u79UMla3uw}3SnrcnsVF5%dA zh4gh3!oo&yUtDXjz!T=d<`7RAwId zo+O&f?~(?>62+fE00QiJ;W(_r_b)woapR_C42Gq)9#YsJF!esVw^*j+X;3|1{=(dhyH@)n^kaqMLiwygdfx_`T=z8OlG|@nTK%>Qn&kiP>3iwSdIg9H zr@e9e{LnMPuW`s#N^Cwq*!aIW^e{&5jH9)q3sm5GY52hTP)JyB<#&)+8HB;hvu(-l zRqOjeDgI+Z0KUJ=eLU#>T$4QswPYZPEas7k>{E;Grgyjny*ej)9&Ohd28qyXXvrd5 z$4W+kvv&AYpr$glnB5}ctkKkEJ~_r=jAK%IJ)#>gx}adA$#@$~%^DfSjb_rBc*|io z#spOsPBpkIFTJBf+_E7ZI;sM-B$@oZ17Qkr$z7&}*RO|-KaYCzU)Aa=4khzvi4Q1J zm6+dQ1f`Q4j@>B~$4HY(IUH+8A_K#lfQ2+VWK`uxe7a2P6`Bd>fOj+3W59T9w zr%qJjYb;%{DyUrw9`W7Z+R+NrEFH(f`We3H^FmhGDOlhuW`ry{s>uX_E#{wIs7v$- z1##Qg99x4ZnC*G03TEbB-yYSN4qWn@a=cu&5|~z6gl0XiL!voEe&}bszlx`-l{{<9 z-Gx3la2rhY-Nhl7b>`o8#jRoja?rOLP*HTbC3|JCjgzHR^NrZ&y9ti!q1aV9in-({ z^~96|xfoX@HdQe8dj`BAKB~}~cGFYeGt;-BKE~kS_rn;wA$~@<7rh6&QDSZh>8FZj zRhnNia{H}F4AUqkY(H-@8nqD@k;$g#P3Gq&(j&d*%(0;i^cUNU{zxJ^`TlVfuyx|9 z#`Rb?OC%cSL+%jHpEc_+)7woF#TCP8VvI}nZjLh1fM@#K-`r};d>J)MOPd0LcG0O1 zY}ett#m?1^9GNFLcBwYBaZIA%0|7`Quttu#HDUJdu%%%sU(HAvi~>G5M&+>cR_7yF zsq^3>O?JZ2i5=>d|M>HBJOKsQYTuv#XHAlBU^i$VvfE69Gau!qL}NDp;khkY|YgCJw49Ve} zxEYG~IZ5;KS_b^wUjGU{0c6%8^mU6cd1t?kBg~#&KJ4Hg1CoINd%Sw5(@5 zp{c^Ek;gN%ysM0R2;(l9=&r}_K#y=OfFFCjPg>^Z!f#%1!Vt)p`{J;Ne8?w40qE(# zb{I&;)M<6+emnihM4Pkg7$V23Z4trk6GDsMgV?i$MO}F|VSHSWW?`25+k*rh)f@VL ziyU;Q1~;D- z73t0RVin01Z$(>`N|7^~n<6!vGsbZME zQ109mGf^(n#3Bd*$% zg3L(2jisI8RMmwX;!KxqFe4LhU>{(P>v+dg?G$lC}I^5@Tq)! zpYFucA(1gV7nO7_!uMY!jqlgo!9sZ0BkGpbC8^?xW7jd3O!?kaxzLQJk%{-)B&G?> zV<}s4gB6U)_2<#?Tu||*L`&^B7n6NUav%SKC+r(l-9D^7!!XCyaP$2H$2ay`~~!se0kXRi>WF4 zSk)1-UcR$b%0Y@IQm{pIyU)VED#nP-QL<}NEY2*uzHnK5E}C#eJ&ZtY_wOkn8nY>I z;t5;SiWmB%DnXd570%=zYZtZ!w02E+*7_mBtisMj6Z%J=pDa(trDY^4*$RV}v>5U2 zaY@1OusyA?k~Bvn|1$E^5gy6OP5phxq#d0n*7=75xdUiTqtlHx|B{xH|E)90W-Zn9 zMVu{DQt69&zm*t1z-m2cCRrAx1ZJ=ynvHt59#KeDzD6C1$*BfaFv{%jXc#_rsdQHbN*)=0E{E6E6Tj`RHNOw&5Yb!e75nu8t ztnbGG7yu^Sy#_kWcG<9KNNn-YN-s-2*7SQ$5XeQcVH?Johm;0yam&C=_2{J^2TRE zKRoq6MNFDMs{2cP^Fnu({BR6uj#ZV57c9}7wJc{vhla~h>(mNN{lda*=kdX3b`}HZ z1Y<;9n(}bT?mrYV32{-1mP=Q)#KuoEghxlY{2FhmSd){ zWQYfS=#UV#+(kL{vS=uXZCYWYW$Bdu`}o{pDITDt@|^RbR$DwZd)B8?B(+8aP>{w- znMVKSzRBl>qZm3F87*{56G2}C?uKIqr1BBrxW`OP{)*K{v1YRd>J7INELG9;)}`v7 zggx&F88Zag!A2qA@dR{6KHK5b;;Kq3T2mOWA^gUHjdWoxRqwFK)WlgZ6-xIco9o&_ zcBPt*Z&pBn2QDOp!vB~6NN%6-$jwGaN`!Fx8Vc}72biIM(J1%u;3Sz2@J#u!tkVc7XTp2-7EDJ848Y74$cmCToNF$gQzQMgH~=wcUWTTZ zBRi|<$Jb{6&Av=524fs?mcMSS3d;b9WJl@PNUDEfqxUmda^4tkiz>OJglH#)L-jNS zo}1^OJ~4NS0}<%>E-#Y5PS2j4?6|f3m1aR=aKi{zwU(me*XTHO?$1KfoP$bo{nSt7 z^oFGDv-Y)Wb*llQAu&=6_*Wq6z#B*G&5Z;><~-goDZwsq$8|W^r%yCIGfR!o99DfN zZ-!?^cRtB?=!9Mm$Tsi5$DNYkp`Juf!Y~G7ZR#J{Y8?QrzNx_rdr?SZ{u@=)>%= zP$*z+?Kao|S&zjqC^1pGI^&nnynPtb1&kr1X$X~o?cXmjsfm~dI$d8*F7`fc&y7FN z!9?y~2|fSi^ar^_06qb@fOO*XRG?j#L3o`LG_KZGpAQ0wGB0y3GA5u#*1vFBR^0e8 zfWWho6fgmANj0b1F1UUWY7}-PD{3mDd|@bEk~oYu!~}qy3_Qh8mN*>%7G^xN0g6#g zlaawG7680tG0H@Ww4&64qRr^3d-{Lpa{ZVoYIAG;A4y*s6-U!`+r!`t?gW?M?h@RB zdvFi#?hL^#NN{%z_MkzBK+qt;gS)#0=kk8{U-#;@x>uj7BXw%;T_3(wdWKXep8Qu2 z0JRwD{O%92#XEMPZCS(<)t~vJ?CrWB_oCC|vO- z9xJ1+DERSBkZm3A!8a0wyqK=HZ`wtk5T;86NGHQ#?hF1U0yts;z(m5^)z#Izw}=QP z0O+Pe0Jkmb!yDhfK746~T~}Y>&H=St`{?^S0yrqDX)_isI_EAZ#S#bL5Ce-RKN(sp zBz>fuODPK7X*R6PI&DGMR+J5g0`*}ApX)7jBkS(8Ay(NiL!q0@}YAq4WK%DEd@$N~W0{ zbn&ajG&c~LH#Jf{K8br0u}MeZi%f^0yG#u6xmDFD`+wXq;*Pmg9etHrjO`uhtRO~K z+3-+hdD;3g_QsaKi$6iiQ6_Ip63KA(3W$oy-z$lZaJF25bPPD zoLng#OlXIPYFc!fcQ>pRl8T{zU!;VX2Q%f=c)~Z;Bx;Gtz7;Yhp~p*qsc?ANa4jIr zL;WH@YB-6G41#$pCLb_b*8c(n`yQ+WvBf{H^tho2auC!HdCUWha8gz%lL^9<_5&19jFFIY}8k-3S8crS5? zg|Ag&(qsFgDY@7mHsMUwk1&O3#^Sja^H^yR5W`50O)ZTaxlD0}pz4K0apH(j4>`XP zPre$#J}1mf#z-Z#RoqHuLg9~|5nq~}F{^SmP95k6)c#gMnH*#|O6Z?xCH4AVVDjEW zI>zN{l@Z@FgL*V|$WSrv>(W~hv|f|h@Ib(LDU3|? zCop8LEvCWBm^{!tF3-e zD(!zMFmVkr&My-ujui@O8R>5kn4@yZt z&oJeg6MfIzzf)>%w*chpdjB&$)CmFtBWwWp`873t~VptYO( zQm`v_TvT-a!RvCbM0-gx`5snuG^Be!`~zsPzBT<$mrCAT0e^eZsu^k#(0 zCc6z%;PLq41i_EwS(Y+)Qs=9xert$Ks&Cjs7A$HK?amW>M@VNeM$gFCJ&|~cnqMJc z<=JQdzu-mTU~j5fzdwmZ4TAt_vFk3(I0)mJHspyu6pSNI>O|D z{Nfhz0IMSWTPv`x%hc5#6etS;Ff1M}2~5}lK!D(2OO7^#ikkvhcS5IV;rWAggfE1R z+?0q3xC2yX5OO&BiQc_+EJ_55V1b0t4cv91$3`*YArLQ-M=tG8EP^{^DzsiM@mOM_ ziNQ1BV`amPZw;0r!UCwU@CkS+2@6IR(v(n%0C=a3GfbqPk>m9OaeHB!xaPAs$RAM2^A{R3=I@i#y{R7`c}$1U+CUZnY&%ATdai*70K&;)XQC@1fcGbsB4#5} zaAE>C5L+TpgYkm@X&o&Cm_ubwL>+^B51Y!tMnS})K%`AkNA>P22Y`OTmPK^wiEte`y-Y8C>8 zr4roX36wb%<_Rv^{_?N&Lg9TJcDA5cLIVp30AiXZj!b{97*B8v5M`Pm*KyoQHflu0 z{2rcdCvXD~yoD?h{YVykfPht#7|>kqMjkWB!34g-UEXjZoaAzR|2ut}jij(~jKDr# z_ZeER2mrosh1W1Z)S|y2g&oJ+!5tmbU_N4wkn81WVUh5@B?lu~cSnG{#{NQ``vy&Q zipNVYb=!e}?XNZucF72rhj%zOEGSpod3JBg({CWDx)lzU?W{$gfEuf>@vCR3duaRh z`?$&W{NLRFL5x2I8ju^=e1MDCl{$4RS9ajxa`P(ec0~nr-DGmZe}91hNQ60Q_LjUW zKdz_&uw9;Rt$m>lj0i9#_Ka-G%~D7ut;72m0QL5@6ZdXn>{#=6ty^T*#SuNjC2iMW{x?*+hpC zF0nd*oh&)}HYA?*k2!Ry1tgIOM9-$9d1Ivv@hLd^w*>J2fsmYGn$1kQnfLIF{Kasr zwhe_0{Bxb_Sx*DzlWSjId`C*(PzL!nRLWU!z@vND+hlxWh4R3rezAI3`6F)_oHxPS*h&~R@5THO!%U~oO26-Hw|1{fB_Ob&HXT7Fg4wV?67f`gfF0XUF# zTn-=tofp?!WfT3+`yO!0;2k}VTHl0hz;&=E5xUY}QvUG+Og~X2YDrdt*C%xk( z)I5Eq&1JepEEbN%scqR>|0&JbjYO?)6(f!eP)4>?oKShl+hKenEbOJU-+8L^(&;TE z+ftn}--!#STQGD?R>k?1%rH{ZU&WkKri5GSa4cCtt7Lm3apwxBYwgIvz#Hbt2BoSP zSNZsq)H_-MXJB)IUf|4;6_gR*k z4OV`rE&*o1dL%@;53Tk%WD7$S0}68`H6a0V^tb?)!q!jf{Wnx_gz2WCKqmPM{ZKs}dQ}Yfk;9Z} z0{)<3_Jt#8*hE_I9j9ldR#2giLljXv-b;bFIk$R?soDSzpB_L~f>j>RC5ecob%32t z@RuzXKop-GTack5si#I;UDmO2^Ox4)?_=jQYu~e$v4=S^`RgR zmNW1=ci*4qdjR$Y(_gwZD*B6PLjT*|^1T&+D*i~2r_{IZz=FllLK)?nl&1?NaY+er z?g@XZMa9`n2cwds!qpHX>vyVM`hSZe!9#sB@%VBMc2K}pVIksZ77LbAI1fE->cBGH z?KB?Ed8D2vA-&dSE#&1dbkS~RD>)%LHKW>5T2)4>V$4=HsuB}1M4~0AQJ0R{SuS>A z2$@Dnun>(4Zf4myCW5x*{G%Uj$u=uMZ{2n{&u>|PU8$$QS2zx>+P4$eSPfD5%(0v3 z9PbCFTghce)iWFy(}=I3knv}?HDXdwl8Yi|@4ro_w> zZqIo|aey$18CmSXY5@hMrq=gA`>|c*LH{ZBb~f4-vPmIgJ&wc11TX>Ep6dmKQfK1{ zfRT{BCxVBGdFAlxL)*V}{b)2GZtcS(4wiI z2uf4ihz0_NF!3;L__VZhGS`aH%+SUWX@Q4LTQmR&0U@qOV17449s^}(qfm8ILpmm@k zprIM@jvn5VfL)e3&KCjUoTYDzaQ)`@o6SD2|AV8UU^A-PVYd{`9l!Ef_XEm0W17rN za*aQh>Hc|<<7-By*pN74${lqx4q;8@ z8gR|^lksemufC~_=wqHqZonU@;A-(R(J~;H#Q&%+9I%~_?ad3<_cOeWFciRX-rZ&* z$oma9+$llRP-+XsP-fxV%CyFV7IH61SWRq)3hZ7SVTVgrU=_eqLR=hJruVLXcb%gb z+D?Rx?f*_OC}7>nc9tRg{WHdV^tAttC2SrL(qHN&Ai9^WTR!xSF^drBd_tAHV0QZV zrhC?9VDnC|T}&U9Tw@Y7CSCk?MhZJhVU=z8aA5xn7NbNK)g+4V{V1l@0(ZvYOQbCZ z9`!e@Wl9P7Kn{2Xe`~d35qT;v{Sx)*Y{o)(1HPp+PJPxTd_JU9L%tJ9Rk^YYUydB2 zuVXpRsX3>2$^GM{<<_zkULUpf)13qDYt|lW3~J_CtjLMrmOg#t8kU>&f5t!jH0`)_ zEk>moVVY6;=_?#$VM>fK`K9n`b!+Pw@kwQLxs9iO#e2tpa76lbPwLr%|M++-y1{02 zKlCfix>e*tF(GfDr~IPkj6Jgh^f>GU>$S!#x)2}+yR6*hnT3D?f*VEa0@?n3M_2b9 z)qx{7+#aY6e(5DDboTB1DYkP@PnfhNIdd5&nW99M`mSVBKX>oq?_lf86MTEKL7%6n zx71!SKida#p6i;cPvrh?qvZx`#F_8-e?D0w25yAzxEuWYohgN;tSZf2v2#CaiV_aog4ZxATiHgzB=DkT^6hTF6H>B zb&)iZr29G6RU~mClAnfAT`y1j^qB(5OE&l!St-PgZ zq37Xn4w7!1e4nBnav$=~^)J1N13^W_$02%9W?Pmil$7r1{)zOz*}9}o8}!6|m+RD1 zw(+6sznCpcfDOBAW3rVWQ8)lIp>)cRi)}_fzs9e!j{^nvuDv!%!~-D}A>%7;k@03( zWLCchTQ48zQEqD=J`(+DZQvO)2?$VB7F(su{njuj*guOsH4Ma6#^mvv5fRPzzE%=F7-ZqMS4*A-r z{c<=L9_xAF6?@`)p0QhccD~PDbe>v${4Hd^d2V{AKXGe3l@qDQVYwr{?O(yr)$bwQ z&D+qt{`1frX)n5$otB1{rT+}r)R?mQ?>4Rwv#sNKA4Xiq+yhNbw}lK}TnA&f>Z-+i z^li`J_phg3Pc49FTriDV6btyn-Ye3>o1oU+&=3sy?}WKm%rHhar_XxyzxaSl%Og`c z!P874;zp5kpNAGPlBd`~E)OOltTZyY>=3Q#1+m^T=4U@ zVu0!Sms(NIa=0zr(D|*4?%uqUeb`OXoi2|k5B5nuW$(??XO7jN`@2=y(z}A4r^LMx z*f;FU|6ZaSZtXYd2ZWH;yh~^X^AL!LIZd|sxNK@aQE=|n1K6AMOAtHDH~?si!ljq< zBpP%7`4OLj%7sH*enI#3s_yxOzu)(F>TMpj>LVJDVV=+OGQ5cS>89WNXv|w8C;xFm zk$>L^=lu}h%PQ4~;J)X($$p*4JVyT8Y|R%+v#X>o%t{9A%gcQo27*}Kg1&1y3r{8e z0|TYH->;`qp`iu_f%Exqrl=KJt9zFpHINU1ZPj%B3+^9$7%1p{Ie7U+g!nMjD;Aj7 z#qING+;H$VW&Z>RZ11gap5*-`vf<={!!|HRKvE5Q@_L=Pc+m`g-u(4J{KDsYMCW=B zxA8ZWb$i=wp#9N^>C-Uf{mn>!WedWV>nOfYzzD<+Z8IjpF>@dqQ?$OxL;+4UA98&{ zj2ra6jw(9AF#6UTtDfcz0WdGUxTuX!KS4bHn2<-FvmcDteKox51gp`U7Xjy6IuG@{fo?LY#kfR6lO$MKk299z0ykP%$W?SX=_}VQju<$x|UM%Nb zm;3M9S0#V+R!Lf{{9qa!3J&eN{&Dr{{=9l#ytZ7kLK3%HGO>CHR<-r%&UQ-`)|yE=qZ}MqH#tMKasmnf343 z#9DC}sI+K7y-^(q+wU@h-$n>74 zTzc}?Gl_LLleqr;xPZs}f9$U})=E+TKKq6>#TpQx@w5aJH$iqdB!4g)?4@B#_8H{u z{|lB{Tu+Rt=SgtMUHo!@(dhbe7*@;#A2 z8J|TQCpG!d!P~Qw{)u8mZ^66NcMm!6r5negh3dc22qy0ReQ9ML9|!Z)kugnhh9~ax zdSB4Y!Vau2sIX5&iI4FXzIOTpQMnDtD|NFc@ig9G(I4(tsNrJmzOFD$>z2({6}{6P z*B}?m{nf6d*ddY=ViMxv^#}S1r;X}M<$wzq=@LQL95+$T+*!Quc=?&k<5>_`dE9JkJe{+fwXkkr;nuW;0} zlMmriq*JwBlDRAe_Y*_t1^;vB`vbu$_Q=bW7$-56g0MVS$gd*?>(ZCy;tkaG(KT`^ zZEN+@h_4VM%kGZIh72hOo&?fZmXVxv+N3|{D^%#Vs$z}T63v4EaDiscsq=|~e(sn$ z;ndLgmTZ9J`C0I;*|Q1^koi&ol-G0ORfSW>>dc@m_0g@f^YhRev_D3JrS=&?>q2z@ z;pSm0UQ3F;Qg%y@Ulq)US?Akqq7&Nw92VrGc_w#1rvOY5fc5KXfiYLz4u6UEhm4<| zc@0s?rK;9!*O#izo9mthsI9!swa>e*>eW~LWIwvC_u8g^cZq)7@;%GH=T&Zk7T1l} zmGtzqllHi6y>o;A`1*;$xI6g1c+I3c;2yK*5v!Ks6`$=NQcw5m#ZFz%^U)4we&W*W z%XRnt%rcdt%GYS;H|UJz#<@0PY#@%;ld>lJYDaT3U19&;n&H}i`)bV1@HJJVhOu?k zn;&Xka`%2VzSv9gM;z|oBG=`SceriMu_=r~aPm2AJbqu^!OdKoE!`_7@C2NG35oDb z`8Gi{t|9TGZ4U=4WNyou^d50=0CD(<6o7F7u&I$DZ7o;VV+5(5 zh@S+5Su*CupLX>K>(<(08v~zVtyj;j_s%xTZAlh#t`nsq{;@rt_@7k|uK#;^wq0IA zQudxe4Wxl2a*)*-d)bKmcNYAv=V@a;y{Gf(G5ED_ zC*h67yMpxQ0%B~zPunlg6ie>m;4+Q2ordi{Kg>$rbG&S`)Jmn!v$E7$^slr>H}r-4 z%|`hhy_q$z`hL)N7FSJ~o*dKSBu!B&V`8nN)UIz$II-y$T&D9MLfXyW_M2Rj8$Ih%+cbR>b zIzVzoq#Zj{kHc@5tTKHemtfpy+&$do=_QXqL2dyYXE5vlKOr~p_QPj~9XZCWzoqUu zzj~!xD+~!Vy=5C-3SL1qfo>LY@4SwUJ2R%8YK`LT_BK1#>ZjuO(MgWHk9RA{9RZ(3 zZlX1XZPvV?io2f2+n1dLF?h&d*cdtM@kV3n|Hq=vYS*=?@kd!QVh>u zYDmhUjNYJqupe^W(4kJ>Qr~=M{H~jdswd8 zkQ}0Z%aqKvtl8}UrR6)dlYkJ`XDne3>@}hI5YV-M5sq6TSm)$JM+SLR(3D1l>kGA8 z9P!;DY$%-LkOTU)lLA2QiUIWxJDFbeF2HoJ5gUa$?yj6*Z{jg6H$RQ8EzGVW|9^bi$DNQ8j{vm9qudQL;lcbOtwoY z1F7W`QaM4cTbr+i_r3nh#c3}BF9P4k2)Q?%S;V-ZD6ya8Jw9|p30_~{qD0?gPvpQ$ z?2BsQ!0XFPq)BkVJqpiLy4Vw}Go1a+@O`5uao3nZQtG#bAul!V8Sg?O9;==*t6VP> ziy5f?v2VFUMn=@s8EHon&i|u}$N7^)All07veEFpSm$Yqo>|_{=R6Pta}*=x zaWr&rZLNBX4*THJF{KT;>qZ+x9nWp3PZytDtQ%fk`?R2+u5QHIz-OTkco7*l=W5>r zb+G<3jK(x{Dfqn=jo)t{Ko)P@j+1Mu#u=%F??guEWGGz|ZDURTR&o&nUrm8OOmjUw z9Dgi+xG)Z)JLPxtTAd=2k`iy@d=h!SShS|OP@I2Tv8q}~1byHAy#oC-^cTAO{htm= zu=mzLg;y>B9l}AZfA{=CZ9Pmx=w#{E>Y5M`dQ9;}=srFmXeY^X`R--lQ((EaiBlzWXsV0Fv z`21C}CwM<})Z}%qCse3Hg|j z3m!8#7jjw`f`9>mfJfH_Q4i6`h3;(66vES+oN4D@jQ!|4N#y*Kxdt=*dBRLD7^Wrc z(KudrJF?{Jgh_u?sct)iI$p6OPiL@#(V~#9fhpj92RIP1UouU)-1Yf1WA9@y#zza+ zm|?m(pWE*rPVU2Gh)JB%XIEm?W67FNJy*@9lT30zx_($}`%}t)3b<{q2RKm0PJh^( z-%gMp?eFRYY~rbiT;+_K4O+YAbsWJI10OAj;;xuJ#ALj?vIi%SErY*4z;n0TN!ymh zGEnf&2%CL9J<9jdSnC=pI)hJ{u+o>p)R}Bn2@LU+RuneFKa`q z!OEi``>v-g_&(NI46#Uc04NxJ-H1#V3p;v?wol$Z53Em+lh;9UkZ5PXeVy3L4D_q6 zo4h8K7t$tMm3+c`H8O$c&>pjXGoAp<_Dd0sVr5HdIiHj?_enMyX|ZalH4~Xl?M>nX z{sQj_8quI{0pdG^T20>zNA88HTCuthG_VuY?_y*{ea=kLDoJqi>9F{Cq*n^C9+nz? zu7!074lznhWZ2R-G!?FJ2-ww;$|BMz26Vhmt)rSAzG42KJ6CUpy& zYjs}TZ93(deF*(3q*+o6*=Zwicg9*?;q{_BSln7doS#Cw$}4>Q?53B7W^Ff_`xK=<8{mV z_3@Ra)g;LO_44_Voee(5AcCtV&BKntIj6(5IrW_Ydvn|7{l2NtM1w~Y`(JZL*@r`C z){)Jm1$#mjdI*iGbG+rH;Cr*>AL*e>)uCyijz01gMNLQvH-@Ur=4w|;Q~ZNTSY9RZw*=y^L2~B;O)Q- zC=hC)zP=Zj#)%eYPNnEnOg=HUE`I%By0!qD>&Mm1+(-6p_VK@W2!858+PX+$NBm$C zcrmDoq#Afrxi?J_O#0+{T$e{rlm9{#d`YwXa`TWc`h3wN_Uy5yvEJLA)Uf}ly!#NW zb?`3WQhRMdmx31F3F%Sf`A<>^tNa+Uo|DbNI~oN)7K6ODUm}ptruEJ+?lxXGJ5w}r zx!%78)=-vDG5YK7l;q)l3duk#uEG3<1%&6T6y^C*KjY|}e1MDn`iwM%-qMU{N0@Fc z8BYTPQJfE)eFkF7b$kw&>ZfQ7uK_^lGByDul5XL^LLuz;cuSQ(UuU>Ij_GsT@;5=` zA5Y6a*^_6v^QQdnW8J(i%Ar+>|LE(VyVgWv8ehxvA0C56mOWZlx?CR3aWG0fEnhdh zC!FOLZHbor<;u&S5B|RTI9RULA@%uv{E4wYpY-*~hzRDN)R5=AnY+32b_?c&dXt=p zTiYAR30*RSpo9c)&wgu2lSyAawz~jvMlD{DY4Z`x7}^o@xqyc3U`VV%X)KMtHT|tT zQCuCq?0bg5(jQ9x{}YBvanq~F!{lbWXECFQ>bG@3D#s9r4U+;7-;!_=~acIx% z#^T{vg6KmuDBxN`PG~AAnDu_&8u9-=X`&Wn4v-zl%e~-(3dVq-CHKRpkJ~f%m_d(! zoW+EK4{42q&@KX8{_{~`C?5~@&}jaO?|`WuxIbgS{4WC0W^m2@uuJbG-hFolssE_q z_?gf5>J)O0p)j<>e5De5z&Xq5ez*f!4-FRfzFkJyK0aAXChtH0Yw;-Lf67mh*gLR9 zAG2rac6)q~AbPhSx|S#Us6r#?f686-kiW(@(`bE`+>o}Gw+vWMJR4x%J@x(lXVKm| zl-Z~^&DA6L_%L^@Z!!77Ev9QQ7MRqqF%f+%NSy${=r4QJsfXYbup zp;uke^JP-8GgnAP=iQ^GMyZV@5n5BVttg+bkc7o|@68^gJ(n=1%PC)~uW$VuvZ}qW zmEGT~2_mH(5Z83Ca#apw?~Qp~VGym){Mx>)D+oJgbpH?4T@A&i+5g3qoxN>Me|xoB zI``ZjHF91w;H9vb`Zd>;~$%&e%z`I$O|WA^RFGeK5qMNDYt+qj{}cz zE=`<`Bs(`^%TrvC;5f&zg_Gr$=FPA6 zRJkJ}gl}^yk7|uz6HMYO6FRZS`hxh-HYw_GIyFct$!ArMubK3z~Er6KQ^y%;dKxYC9d+t54$us5}hyrK4q^k(YzFjuy{WWh4^xo zV*uh($W8b`nuu5p%F10cTIku+zFM4r#SkZX8AFxQ^FJL-#rf0UPRB2O;1)b!KLbPm zeti9X{0CC-=RE7?6A?XKKTDOr%#IJFfXd-EMuzi=l!9iqbm)i}phc!-Ij&P}HqJkv zGAH=!u%8*%)zY)ims9=2h~^KD$!x)$pZyn2L)@-9FhHdNYL=C%{CTuDP^c5e+wg>l+kCP95NPR&PyO5J^OXQZ{QNIt1)rp@Qg?;KH+NDe-nW10 z`xqM@bud!dT5u>ngpX_h)SoaS5UlIgZ6sgY0#9Rt!CsUeXs}kLThfsc|A2gt0q6BLFx(drXS{Uip z5g1he=CE0t2Gs2=ApxsQf}HQ(>6F8D15;o|y2)IrF}+^MfWzi3Csej-k@~`g${N~K zhRq(zj2 zHER(A{#I*k5a`@CbSZf|CTMbQC5_sTcW9Q_j*1Kpozaw?`vg0LNGh7t5?D2k6Ik*g zsf}5um8OGJUbIALh7VsxwW@by@&W+7aH%N7&9^ghK1OA-7KGK?zV9cdBCaPkS7%v4tMAL~9tIwJ9#7$&W7>PT2ky1+a36l_2=5JXgtg>Tp_ep^$=&o1Kpm;tzasqH{KCVR&(?GgOH6xnOHe5MnLcvqhB&NhTDBpgcZg&xTq~?^$&1+oTI_8l*_7ntQ!4GR? ztn#4aso#<&!+#+#P6j!mA^X!kQi9L*ITgy4B$xQ&?NLW+0Ar)OC&17eQ}5{hNHh;9NkbhmmH5$qf~sYLab; zIZvM7b;QOk<$pJ51sGSyaJB6IXR)F;tTuO2Uq;|pGu*UpKh?5Y!mFp`kI4<3;Y`HJ zkbgAd>yi(L>vzqvN}?gtV7k((bE(M1#skmZco<*B^T(PC6$?<`bpX5YRL@#eEwwq}vzh0+$r zTa5Ja-Zw=tkar9PM}nynYRdA-$>;`-JdVw=-QsCQ;U4b1hTny{sABB+rsX&Q_E7f? zcpZPE$?oVb#$VZG{blQixk#)jC0*%GwSIwPC5cs*($%9#hx|1^B@owZYAbx2`b}Bc z+XA%yunFX%cdd*2npM5GItF}fT@zx+0I0J5PJ=~bQk6PBqM)RizlQv`FxqOyLXDCt z9Sr=&H;Ni!BO@NZx`ue`wY(`~XG$)nf3Qtb&PBxDzr|fb_p*k+{koX(bCpiLd4&ON z_HB0d@4xX{!)t7_SXSsOxW3E}c)n^fsaDeoY0#13oUf}yRSwra))tZ>)~fBNzD+kTZq ztDKxe{SuP#I`SWi{_JtroYkBxd-zEq#m`xf2J_poTd+7~bd!Sg-iZ;mdBIrewuTOb zS*1YNe40SFD5h8el?Ce~Dxbf)2@VD)P?t)NE!PQ`5|IDNHR2bC@*|vLkqUo0HNJlZ zqAYs^KHV%Hn#XiW=OZz!36q`wM2&;qVpf65AkDT(L%ThlsrVqnaL4sh3H#46Wx->ix0%~+dx(y-%iW|4wQ^p z8GIF0Oj&Ky57L+HtNc?rU3H8b3J#iDy%7`P<|C}kz zf!WXa+;i=yllgQ?;rMt31iE7#QzAZ=8bTWk54Ti+Or1I5rzXHUY$>p*wb(OQEqKLlAW zByNu*lC%MJ(+*|w+XSL~*{1Q?8^*gxn`OXiH-)K$midT*YQsWT-Zk`0>_Ic?zhJ9>L$`k4bC>sJKeD<3%5$#a$-41c*!2Ns`i;5)E{a!?_qivFq z(M&K85)l*yP@!PFXP#wbK+~PB(mAg(i-cVyd1Yv|Vo1PkBVojYlpYfsDCc>$4QS)} zEvl6f#jPol&Q$R}lh0;DH6WSe(jYBB;XjXw(R$7h_1qFZ|!{w8#|? zNEel-iE)2n5;U&J6bu?Em+*OhXBA3R-%hj%jB#(Ko=UHm#pm(-^YwBIzaI`bC!K9F zVEkRqUGU~>6-)!Er~}<_o4XP<${QSj_zOERgKNZq{j4VdO(e97$*`kQBU@A?zy|<^ zGcGGy@;aSFcp#DevaPcCa|NRq2o{8xSl92dVlpRSRE* zr?$#ST{aNPDgVwV5j68j-!pWt;Fg48-kx&g>)}Tv6=c#X=wmA6S#c z$%`I1#$CWRrz{FX0d7(K6#m7SfrYbX2~@uRy;p>{2a1S@G-lD@ri3mdgh%<`_SG7x~uz zqCQ%PyM|&cd^HDHSJw+7rp&H+J|qZ`=z@(v0T}jeBoUGs_J#dLDuO0(K)kpHoxJTo zx3)}@$Rc{=FW*8oJD5>E7L**k*UfWmaiNV)yCJQ8%s~QC%HV0mZ~Ktfb0-`tcjgS! zlvSApx^|LlGu;_fagj}mT_O-VL+_UlyY#!p!<)A@T6*Sl#*Z(6nU0j8lkVa+J?83<8r0rx_txfy+=9dT_#r&%1h11x~JqDz4S z7HX>=J;oafFGRO^pva{@+Mvrb$ktsXGPxI3DHxoBO8 z0LWDRl`Q}*hX?er;eZqr;3Etk01Sz&kpY{S>e~CC?}6(9UHH`eER|EbTT1XGuq(Lc zhjF&+jh!y_)*FS+6pY zQ^JToeQ)mP+x^Rq!CHKBV_<^~*#0$wDX0~OVLZ)Vw5)_nmxJ=XZm$5IW{klKggW)v zj1Y}c+mnyulcQ}-XAJ2_+8>~_cDf;A65AT32bVpT|8jYKDhRaTp3b8RIhh^mE=dw4 zDxOl_DbUYMriBt_!yI5$*@flJm|mkPWj2TM|LRT}fHYn^aD;qW$)@O!$`64v*7)3!yhJ z01P|NYW>uE%Z3)&PL;F`-!pYlNL6&yYRk-34#%oG>kOqaNX~BxkrDI^H5}x)f$%0; zVOs~a1%YCgD`nVTuCErJ*DP`hqkLM*?4e|O$QbtKvjy;G{7;kU$`Qi3>%OE}{SInu zrMRBt2A{#@miur+q6dr#s33S(1}8*DuF$MYDntN)iAPEkPgL1E0^$x*0=+_j8KV}C zU!kw!dcXjcPL;iVp$1Na(Hm-AM(bP(gHa9;H~Q>Wv<}a5I}QKFN(;dY{b^*JtBGxL zLv9Xy{7%;a_eM!5spSI}IzT{6Z(;-We^M!QGCNXU{VBGlK;q&lV&o-W`9l^%t0)E~ zXH3QoG{koOqkFoRJ{2(M#bZt6XH9WXeRlgKPSr-rsGuVTKEdrneco~{dhdTWstNBwN*Iw zN-(&9?i+BV2g70W=P`XYEMPM9jR0A-jTL*KpEqbD>VgH3)IxN4mBDSl4g|43uHb(I zX+7cKlt*=G+hg!6@~Jc~`grn|xM{0ca1nEUK>d2cut6>Ojj4$T!n-%QucW z=jSCku|H2mxt2Omd)UkejK3wHx+5hhUI~vCBLsb(1OzOi!>qQDf$esWZTT%;Yj3p3 z1aqK*Zj=w7RecC~@6V>x@6#b1yKvkgAryE-pukF|Y9&P4cX$$ufNO}J9s>?gA54|- zT$4&SRjwX=tA)Ht^{15S+`e!^%M@58U-O3xI>%CLwR~9*nzwc=lQ;mS@Jse1xUlw? zE^&bXM z6#^|Z$hZ`p)p4|+AO=q0$f@5H)64^|iNt#m4uwxD@E1>&HEc2oJU&kEUqp4Mz&7-R z=jsDxskeL&6m+&EN8aSIeU`0u65|aVw+jaGrGo{%gGgTUOL? zN!lM@Jm#rv%4QTSX2o%^vQwCq_?6{mVfzu{w_m=iw4?)SDj!J(%O=~ascntmYSEC5IXz}#DjgEqv* zqgaTqAwZa51u#}9%C^tTYx$Z}`(gX(A4ItXASRAvxr+zP$_~I`A?d};*V(fnfs$Md~&IEp*9c zR&|0)Q&nZil$lN%(y-BA5$MnF+x=+4rb)$G2wS?i;_lcK zX7WS`xyuDCl)9~|Qd!O;i`1(6UGn}QAjk?h@8s(iJr!T}${@-$F|?zf(++70Rp#l8 zU1A*&1zhm4YSRqW#F-a(#36o6Y=4xHOKG~l>Z5XYb;qVjCe~v8RM4kkliBATur5XmALXyDW|Kx4c)p=nGn9krV>J9VT*Ux}Zu6u7TX;YB zdqcmGPk2&aa0=ZtGR%oMEit4{O;8q)XSlHbOqD7BruVR}N>)T-f}G5jey<*;1$Rqo z&ihnX!|=Xg7%^`9;XCsU;$17Trlw^4@nAc^sR;O@5#>%erj7q?fK89$$ z#Ti_bk=-J9e3?Rbl(G-L-lkM)H5rUnC1uS5s-o~rns{i{y9!uT%nETd*_V<(@cs90 zB5-iX#yOlmyCIxy*osqWh4deO;cu3PT$^-h(4~&!JD9$!^qxi&T(5`^{e{QCh7$3g zAPo{RbQ3q4t-Tr*V?PCVq{e6`U85;CqBijp%c7rqaR`s*IUm#Twp+(mQ!oUUKjm3f zua$ROrzt4JiYg(K^3y2XkegX(@8`^}N;5-Sc5;{g_g_rOB?+q2Mc(we4JV}L06GX2 zv!tRypXH1Ga175{ZPuVMip^4v+mDv6_$YT_tPF)D1avlo5q#u0XQ}dTtR)p*5;+zG zateB89g=mfoyE9?fpUkWsQ%3cs2b6oV4H(8`>Gf+L!1170F4!*G9z4@GY=(LKBlw4x_~Oc(mus}j#tmXf) z_Lfm`HbJA{gKKbiC%6WJ1P$))?(S|AB)GdvaM$1#+}$-ua0mo~!wz}ByJvUL{j+EH z&oI-pRCQOEbX8Z>sh86^nj0)w6C#ZOeuDOtwUJ6DK+uH^&HB*dgS~?6MI5$B2Gb zQchS?WG}3!MvnZ*%Lf??ypah=Wu%p1KevtuN+2zF8u&2wmJLHPBc& z42Nz_?-~(c+26IlgP}(Q*&@)PLYZpejU)``y8(83dBGXQ=veMrfv0#Zr93H7wQ=k> zXg_=puYP$VJVcWpki$;vBQic($nc%9=m~4-|8DM1HT6O{e`fo$sQ1;tl$$^6G+{rx zx(^wkXQlfZF|ALNt({Adi$MYQ;M6RGGqA;6+i*i6&~Co-3`P|m`F&j7cxantTQktU z_U^EQG`%LeF2<~givh?+q6o^K{DOqMA}+;4q%D8!l-!9VWp5Ku-7m%i=& z2yb02zq71%WWJ)Oy&v9#oH}>eURavvZAh~2xbg!yd~yj{e79cb2FJHtxD9u4eMmvZ zf5adshY=bcHXwvV6-5M$98~6O9{m9H+&RL!XA$5x>Vp7ikfn)mnz32`5D3M|{({R5 z`2njJcU4yG<;xbF;W__f(Iy<(d-(zP9rH82E>t1MmqxaWr6&QPeplAB9T(=gp&NC3 zAn>tk3+{KvI{hS+4kzKSZ{i1jKsGm|+a~<=7ze0(=@HN`|9lWF^lAu9dr?jcGDCST z0lyU<U#+(Pd(2K*&0dEqn-MVVq7Q0sgkEs=k&nS)8a?Hno23;124@_HH1Yzy`~ zHZwFc<#~Vnbi8hg@rR){<(I-VW9BN^ln)p5yN&_2jdij$mbQ|f zQR7D7_P%Ysj01<5Io>~OLu>Rqk3aVIlBxchT&VCUz4c-pF5O@w=py*ew|Uu1h96O? zkJabkK@$SS=q}-rwG8|$kle`)XusQ%m^{^@5hXq_j63jhxw8DR!yhir_%#5Anu@H)bUXuThRW1MA~$G*~z%jBjH}Q z_()PDEi#oOS+y%UA+1`YwZ)9ZakO$g@-EJg`?4FHJuio&iCU$h$mBroCi-g7nxIGf zQ7tL%lUb!h(dX~nnKu)YU}vSQy?Ja=OuEWrl4RsG`h7S=)Z(7uoAcd3wm7J6r5O&C z5b!Wjkm`XLaDER4 zWw_~jr|J1gqek*HIKuW+qwuLhqtI1XjO#@pV!T5>e#E0x@<gMP3AjrR5tTYc`ZeCBEzg3yI59@is|Efv0{DILf>GDvsv=x zHgo+x;3+->Q#wTkt*1stF>erN*v&*mkt{gL>jrW1Zf;vB_CQtC=NJ$XZ7CIexk6p%s(0=NbrK(g_0t%@Yiz)9QPzh&~a8n{^ax0UBbX zJ`t6q%BIKf#Yhq=t_mph1R1Up5o;8wZv3%U__gC#47B5;H5hiDu<6(z#~A8=p6Ri4 ze}%a7+dR@>y^!jDO&ec(Wlq0cuThL&M!;V2ETY)=$Q#~kSNm_dV6f<(Io{W^X=T!b zn_R!*vn*l|!+ea-XV|yLb}A7r zWy4`&cE*&!5l^VRKrLdf$*h%+;l;bC3Ol|Eb)A_UCsaFE*K8+Fbei?8i^7-gog0T4 z^mb{bzY}n|goYoFEtfn`et@bRjTMb;~F#DRMjPK zP=81Yv%(ly59E}S6`XkA)qPH67Azi1nqQt^t9U+%-r7(t6f2wR# zf0|OEuyG|$hcnJ*KPNh}hr>tBtt;gNb4ItGFr5#tpujSGzOu4B&Z!d&$3g8ZPC!0c zlx}tV!xTTzEfYd^h-SiIy?5IcS+)FhQn=E2`YGOMFM0(=_$-0j|LOu|QUpqiIg`F+ zqi8n9hwD%uG;QqsBkbmC?Sq7ej#K6_q=fTb86y-N>x~PhTQB^1h!qc>Y?=HDsq0uG zRU>Gg`^kBV2OzHuZf_yv~h89yo^V z-(|*}tGoJWJP^Y_y9^r0|0=qvtz#`=z)s=1u5XuZB5GihPWwwc_wuf}VRANJ{aXbu z=BZhcV|j%c3r!XuPY$ABRwPW(x`-Axk;VG?fUo^LcW1iE4M$?#ij)U$uFBv5zsWoI zqSV5U9WH#3D%&BkhsI2v^vlZfI&YP#$Q-t)G)xdWjWC=HzG$wChE0Y0D;FhxI5CeM zYxGeb%Y`NmF4w4;5++hnT3_Dib^v?!jeyvhm=vSB`YbXoH!@hxpQwvaER5#|pKGCgx=)HllKRn6>Lt^42}`v23Hg z?7;Xn{lgor1}p{#(Vb$+9e4WQs_y1TzE1AEKWhnBvh!rv5fklmlTth8qV>NVGvnf$ zFYVJzCRR3@-<*W|f;0UUiBM(_Yq+=R5HaC(`qRftD!_K~ED9X3PH>3E*>w!#NJo_t zE*g3??a9sAvVETu2E`D`85js6ZM!8S0F6YMk>Z+MhoMa+IP_gcE?sLKmwBNP$cT^(ET{^Cg#ya zc}hX$%oGwb#~TaOL{~OxWq(kge{%+1c{Mhg;KAg4u@B`dvhvN?IkWXMLEm>_fEJ1J@QZfYs}hzZVNIVvB-O_sC-Xj6U}Bf%t@Xwf>1iza9#vDT^#A+SwUJYj?! z=vXtZA(}haL%HfO;|k}JQds2tqGMtl8Wo1a;rZ}AY!PoSj`;ml!8Gg?b{*8PYHw+3 zL+K_4Mn;g%n)?t}F&!0ktzASWE?f4X7hQIoYh}&FqKnq|@0|=0EzK1l3j8c&ist;tKbuYY7|*Fgf{#Gh-t=S3|XiT742*jbZEkna-tMM>!h^+qL{7GyOYRSbM%#@~pp%-OcF9ht#*7QWL-V z_b{(?$ICDdS0Nv9^31>U^5e^mf4(taTJ>bnME-GRdwxEgISCoO3QS{|sG#`s$Gcj1 z2H_s<*9RyUqnD4?r^W3L=tBvg)x+=VuDW(O z-NXg}j*_FZVZO5Eah$}B5}D7Pr>A8tOty^GNA7E7WvxdKtBh6jE|0tBBx6nu~IDe_8$((cDUM-Ib;L zJcW2RK`CXfDmz#&g)Rl`2ny&fbZm#ckZS;aJ#9SIS#ur2DbJ8O-zj%NcCehMYNkr1 z+bnJ9-_{#jVCPpq+i;7X7)7Rr!$(JM>NDRI@WE`ALrV!JkBMr^0j6_nx=>HTemR#wCuPIa_pH1p26dj=Uq~3R zWTW+yyisTlVy9|Bq(UfJgfA~8@mHIs|0IKJcjO@aydW-w8^UVz>i*HwqKy6+TM9P>IE?YEf{ z077uT$Dsrf+-o>>S~b%#X9o+jjBrgM07G{p1fXZ@>Zk{`e|_Cv&c2{h)`bQ*WmeXV zBaV{&QH>KhcOLwacx@SC!n}AxXnxcOV5ReE67w?p#(_K?-^c#)pauF%whddN;6dBS z5#HFsAWHXVN6Bl{++zI(yLC1r1z!|GnJI4-Uw3(eCFvFbxk8vDPcB3z?w54dpOj(D z>hkFYLjW@Nqlne!ss{!1-Wq23yytbqxYwa$>I>uwWiYQQ0LYsVpz^9`R?nwz8F5Wp zYyXv)-9j;j&N6leZO7{>H2a=RM9sa_%!5L(531LF6&q4OgCAPN9-0H}ay*Nxy~hhCMHjC0K| zSt#y2VJSVg)^H|7XGy&z9whcTYbc?2fbCbzY;vt?6+7@`Fok_2lSt~& z%Ygti38$(jMiY1~CaNC!iaIGnP0zvXnu7*tWGxX9-jaj;UH#=xJ#ifY_GWU4B3n2z zN~kF!buH&mL;brIGXO}5hstOue(3BlFP*5*NQOE-rV9O2ovj%sHOxC|gW%zT)U5hQ zVXWhp$@d*ywgBfMFMdV@yIVb3CBu!N4L}~P@NH(y_w7V+>pPoQ#|@NPXLlSfTF|+% zgEP-}7fuz#n^uKtBPW02jGfi*Z&Fm+47(p=G*>~%8d8m8Oo(?ob-uvrO{GF=*%X;Y zQD8{}rk#hms@ktqV@k{O&D!&e>@2I9)nr^1AftzLv(MO7ae&xwdm|fx;lLhl8_bXOLf!)l>Y zBGV)~nnfmi9AOoz!Oa_BFL? z<=U#S^!`3RtMDOHN+5X7NbxOaedPxjeM7J&?0bb-U4Z zb0w?zK1zJF_smhuajIy5x_QeyGxJ^XsTDOlB^>?Vg{wxnX2ekaq9He#QTI;ib78;)CN?l`k-Kwq9R zyiZUOD>kH!=K+@p*xH#W=APAKZnsfo|DLGL$PhhZ)hj@M*9&Xd!A`}zAg>Fr+XB_K z!joE4d95x^+V)&W({#LfWRKGk%~3rNy^?+II4h;U#LmZ)zCif>>K#XTCE-? zGlgdw`BhE=5B~$9ZKDXrr5BkhIT+{9m@uCV;gh!_bKfT|CysZk>G9`rJ!HR*vS%4J zq3xgM@}|DF9>PZL*w+XlCghR*iuMbK!bM`6!!8^#pg<}WQfO%_8GAWe(So<{wW~fR z4@Z<&5FuEPBWp=thY$-g|DAWrdFMD3CMJ!hK({PkjITSb%1ATjom~n+lW`OU;kq|r z0kJ8*PCh94zBiSzf6M7t)YCD`q{2q$!1BrJXAh<=7%S9X~YeBH|QgC-RF%mL!ziL;s#v)CxL~t{scy* zG40$NJ(&oi$bhkccXFbOK!*Re%OvF8Q|^7$z&YvCzy^}HLyk@r>aM|Fq*8!h{&kD~ zeQ9989Fs*6fmGia5y)fKWRBDgXS+e}&yh=jg&1TH@h{3rNKS&9 zc(J(&b5RckypC6;fCH1==UBO0r)gUhf$O_oiuLS3WcyCCXooT~sQ1H6Sf`8uQ}o%dqBN{%OBZ|m#>Q6&v&MLkT+Yi>7if_ zK~0A*dvd=8zA2^4^QE~NvHl@HkTXC}*xg?#PO+)&Ph=othhALo5bj>tqh#dodzf^r zpErT0o%F+3V}bmF1{LeNaZ>04oUX$a$Vy9yIHU=`k#!5nR<#vOHBh+06vzDy$pe4B~vG$ahtXA~!m ztV3IqR3NdbQ`~>Job|Jv9WwuhAEC!Zi2ab}PHM9hYx`b3iywu+mT{2~d3{K{FW~0x z2ltDgf=9sZN!yg4?VW!ApjcQZqvT~%;Jkop+;t5@*u^K9aKGNbT5g=e%j!Vch`jd4 z9W`M~bb=+)Q8>g|-*&PlLL>|y58-QvTC$^CT&n94n3xAoxxaPns%NC2F*k_tfk_Z4_60^)#8aHxm} z3zKi8xoBuNC0IA(gQ(rD$tlw?cx;$8XIS;VshqWxxJe<2?s^U_nIJ5F#%PHU^v{4^K7vykV0mL@%}dp_?5p!({$l66T8i*?mXj&jz23cm=O|+_#}` zEElwS?UCGb4~~a}2%QUfpT9*5XOV}%%OM6GvL5S?f6S>Yxg`I2Gi)mNTjL)1?L!TW zqe<<`1*4pJCo|#Pd?z_TH*ol%ZCjHzsAfy<)Ko84h5j<)bKGX z=0dHcS*I&UKz6C3NwJ|y<64~R{6eh238w7Q(oAy;>1Ls-`k4=)@84t%le08NZPQj+ap(^|t zG_p5I-WC^TDkZrcU)bkK20Ym#Y#XyF8+?$;Q~P`37ew^k64$Wi&|rCvujD;mvK1~_ zhJ>;tOT$BTaEsaJw2$pNW^o@siS45~6oz)8*NZCI%LrTWiIRjrKw#i}41z9iM4Gm7 z9L^eq$e{Qe-{4I_P9uE~dMNVCo-Zjha}}!RA`QTy^jr{nyzw1jrFISrlI*?tS$8bJ zuq{f(#Twey#7jF(_nuVrvvXknC7#f_xWxIbF>`uwpAr%Fp^Q~loH0A%PGb-_>0`EW zenVvSm+2jHIS3~>;-7M=5z|c=BPq}5cu?TmT`Ul~vjoz^s-)-wWNlj}A%S+Xxyg`? z-t9pkv5v^L3GC0DW5N*pZqh0pKbzyg!7fxP5dEogu2FCwne#*l55gOF7k#>e7EJ)G@U6l@ce5GI7Jka<-cXH831 z3NJm_LZ}Dvnse*-6sw4G8Y@tNDb0t*(cu6ETljA#U4g|om3)Mqq)&NrepA>&Xb5T@ zA>%Glp(^h*04N_ukP-|Fld2Ct`JAH>JMbirAS6B*5**k1)ocEfBm5bpT{-ICNel>6IbD!#%qBioy^12IaB;|_tD~(QhB`Np zo#W%6+*U8_WmKXZ%UCJLqF!-sGy9=!F-)JC<@;ZC4Gp*TU}2%Rr4lM4i2Y14^YwB6 zd!M&%?4VAvIVVYMVa1In13_#XQp;A81ZnjF>h7gyzT1_FP zTU$~)BCj7_jl4Qn9z*HSkxWJ6$a(Xx*^##PVtU^?Cg4dQ0RTWgSzy)+0wW9N#sEMD z=E?xL7y!@i8*ezS#Vi|(bN6n@cNKz4}}AObiUnp@tr(JKuuhWu4roA&xkBL8maE4-?qGoQ z^@Y4+fCqrC3HWK9Hd{aQH(AodO$d=9QZ*$9#0rC}+U@w{z9G}|3Fi$jFn(a9$ROS@ zk^~EyH-YniDF*#30C!0S@xS|eZu;K{qa@%qEzQ>v2TkB{s$Q|70bq;jMKhGx*BWmY9Dph-HDGQEeqs&fL&V0>h~5N73b~t#zZ?Ti4^ey_V&N!sD%;x~n@@ zy#A6Z0lw?pi_Z)Ton>(XpFZ#ni1z>(U4p3AO+SK?;A$Z~=V^Fx0RWN&0;L#JV$Yt3BoTFGMQm_(beP-sA4 z^T)Px0qfC|)o1+p=F_=vDXI>wnVJ=rjiQw{2m4P0YMR?x-hX-&7rXNV;4Q@{Tdf0QyO08<|;2gSbgq z7!4u{ibzDV`d!Hcv{`Xn$*P(R+yu-%9r4t?Ie86?C#B^}gLGgrS|;jJU+Tl{^G=9T z1Q&D}pLW#r@kV@GafeAHY<+ErxH&lnLI#G`GMl)0t@O87kX!}axzo22F%pTkdqt@R zryiV2OAj0qoibEI)U94nF)f46 zNy(6GrcGB39TDI3THo=#Fktr7|4ho-p0w;|f+vtC^b@x=kr;sTd!OQH`IjzU3+b#w zv%h_hJvL@e$7|*XAC-dOXmLzapwBwziOO)D%$eF_St72x7Y#+k6WvO0+#Pt!w&x$XW@0wDO3fbL&v&*rw z`3F13(f5}(O{FhgpF;|vO^fFOiC>$dA@JCAhX!V_^f?eyIs#5huY)q=P9}z_9rCIc zl#n%YZa(Zf+BBB4w}i*att3<}95w+N@1jJ1F>Z3~EjQ?++8M>;yL+(Zh()p@dct9X zwrW}ZgLDS0qEO#xvQboeCsK*I) zI?cJbE4GVwJB&EkH<~U&`rM{(W^>ab;$B4TYg`?tr%TBfQcZ$Co=|d~c&#zSf{R5| zwP%wW+~=m`W5m4e%u7MMFhU-qQ>y;zy>$;j{|;Y*=r=QUN=Qn{rdxrhvot#~{vP`` zHZBk@x=p-9dM528@uNmo18HF`r_0uX5{~+z4Z0^pxl#;4R?KD0%#D-Cm~EOcj%05J$w7 zjw3`RMvAE|UXz!4znkMsz(2YRvw*IC5*ky*9MEI|aou@kd`favpx)|>9vQN{8mTzY zjTxy|@Bh$&Q!r;;hb#7d_^W$FGKJ1sYi00X`a0Y?n!mij#%)%W$uSX#H3?yjzehX# z1KBaA$3_L@(S^pwNpDN+GxkNy0;g*D^ z{+!x8MrqDEsTPz+!Y1iDM=av7WWY89woofO2>N$Ag5k8Lsw5+cAQ`>#Zww47_ULxx z>YY+a+wc|(SRnv_-;SXH^in4xDfGqe-QlWkQk?dphQ5aoj(u9Q9)git0?SwU?eiG0 z2HMW%%c$n~6xi!T{D8uzUpp=k}0} z?LeR9hwgftz02R}`MWqQ=|qbIqEQBU@`V3tSVLNJT^e&oufPv71luhe6E%OEWDXtG zTpvmkopbsJOoIgkfexfH-;HmagdgKKjBl_EdPqo?3tWhhykR|B008Z1feEVSpr_p1 zy;rhAlrRqx&Oxnbpmpj_*;?>4bNBrt`LCl)guE5o_V#*=s$KWhGkC?>k3YmOS>*%l zPPY0NQo6B(8nL^7#+B{!&D;_xjjjLSJGgIs`NQ6P_jm7b-u};X=#i>mH>(?wox=XJ zqJ=PEu%!h$x$zr&yt0E}T!BYF*uxEt3RJxRB!MOTqauU2R-{J5OguFj|K9 zJyn-+XXgVs69PM$_olcd(lI0a_6Z-7Bdz;jCgk=s-c_V%aUW|Jcy!AC?x)U}>A5BI z@WX;!T*V{YbjbXDjVZL_Zen^gV|5h#K~mwcAYLTMJ8R4yVho`yvTyh|e<<`d zY=^&`VpD)Y|Mus0!@X-EHQj$q;nQW3R{Ax!IlA&AC))UENZ)bcE*Y8Y_+m-%Z%0Ou zzL3#k-fkJwuVOtvCLl_NDz>>6geLQdOC-?c&GtrW zjy`(8Ocm%ndtyI%u<=WqYv7@}z%x%(jzI7@nH~UV>C@@FaVD52{gFx)2vzs~i4_l9 z)ke?Z$N0!%#ga2Y>1w3LsXc>QCGGXupo(0%+EP8)o=y_Y*+CM^2o0mM$S?Ts(V+PG z;W0f^M7^r}feN}32h1wO5-b2d^605T$fMQc9*cYig(I&^lrpQJ6HzLctJ2ES(g@GoU;qpy3|QBF1bCSbm+l;IohZ{8=jkNc6osH3*!IEs%pmblruvs)a?rQyPeL%|82h{x0w8AH8G%5n-%;tNFNA z9}JH5S|A-2kY|fu=pib9G6nB6+UtKjv_=-n!_NFWSw$d1WTSuqs+Gm%F$}7q2GY5n z7<{Nr#RFxj=*i>VV5Y(5B7C-+yQTHA9(A?erZgbq+SQ=F(y19Tiu6W1Hjt&dda$)F zA3nzps$uTe>0F$M-OdtgFJ<10fVw#RC#Ys9^W|u|KMzudf0GIY?yYXrHkbp6*=SW( z6M1Nvg3UM3Lq@0r?Nj@r!gjS1wI^Fx{Er6#0w!IR7Dl0c7_e#5@&TfefdNL$X{!I? z{nPpCT~)OVA!N${tB>cGI#(jCg;ouTjhT(_kc zG@vM@JIWv6ND}%Vo|!=)Qc+PvXHMu!Avwr5ph6+T^!3o7|E;npgyHMeWh?42`Wt;c zgCA=H&kX?fNQ2FgH^~9Es=!9no0SCtkbw;?GB95S8(wcr`k!Tm_TP!$+l11>Om{uZ zd|ibB|M-1|XgGi#WhbZqWg zd*;Yksj>9^;bwm9bUk2&T0+cr)CN=PN)-`?(Tn(p*%Zxs7M)5Fg_atmJVgrUDPh)jEF1g_#e{*t()NXZ@DF>e^Y&yUYs+I-^QzkDSsSim#V zAK-T$zkKE&3xjWmDM0)7$;=R+DKt(mV|}_Aq&jEM_gNGMcHol78a7^p`Owvrlwu$G zo)Qz{y(C3HYh1Jh0gdY;e7nwQqD$M=6SJ~d(q;j}$zn|qL;`YS>9^9{kMtP?c?qCm ziegn~ZWj3ACN1QupB(dxGwcrUT^H*A5T*aX`9~&(KWM7LbP_jx%VNH>Iv7%tiZ$Fp zf1n~b9r#h`{@u}`HyOe>MRpYfvl1uc5U(MT&=+A>{xel9>|6y%NTJcX zrmzx!$V)nXFOIc+VzfJ6y&~z-G!s9%&`9BPIN3R+ErT0{i6CNjW;IYt(C_3L#%3gc zWW93220PPhCp9gl>iKKaaNG~6*g4#FJqCkh_Z%i$nf4Jc-xdEITQxg8T#hjA8(D9= zxicb+EK|TLvsOtriV)nxTK&XTPM;Q^CyBkurn8G;LH9H36-Z${pSGrZIgCTz#&*8$ib<}e&h2SI86p@lM%P^SkM{Y zFZ)WL*td#ev&$Tp2S!S&s`Xdq&1ozweXSmkAXC-um)udKXhSMn ztv4k7OYF;tK4*Ioxtsds-)_@)0tGgb(4**!J(^0wn(+@|1ihs#}aqJ}w&34Q_?zc;=;t z+MYo&Nm1dGOOr^6vmGZ%aw?U!j>h^I!Ls>c?P(?2n6SqQlOf5~QOZ8yP}l6Rl1yR^ zgJkb$jIzCHf;Zv);?YbLx-%xarY5y=)WHY>aa9KP0NivYRSLCb+6c79-90pNWR5w*MrK z$aV3-&Dqgto+D=t*>$wUx`}JyPnBs2-_}FQ8(H#A#jvm)L&p}^wSVX+V3d1w?D{FM zr$2b9CunYQ>5QLy=k&B3>sR0OQS63-%rH4e4;cI$7TvuWNEq%=&c3@w?>i?cuTf=N*J=G`~TC7_u$g5p4cjloZol8n>O?U4bMfsref)3r z39*DKKRww}RKdJqjn=~*=HOHsz_q~nACmv33%q{+&BedJ|7-65pW2H-6JV)VEwQEZ z(~8>RKkel_4=8A9tv$4n*qqyxNNqMo|8I~DOd+g`2mNXhV;9qm5*d z#u&;4-q{rjJ2sUW^Re7H|p4#xiouhEGEh5WC-AV|#*xi^;kB;Qwxx}>Gkgmra#~JeS;fa*_ntIs9oWzk84Rbt1aNwD+be!$bFlwN zb^Q~BA{6p-Wz0!@r*Qk~tj_hTb<@HR^hMI>LAH~ceoEf#w|xhmz#z!!8zX*p+oKuJ zLf)u04ak_+5>%%)(+?Q2vNUg&1Ncy(5ZJDPApf`V{@W2~|FaSPPa653MaSsGy*aeN zocWJWZc+Hi@a4X4fFk#gc>i06wcSWxKF69NQ9QVlTI|Kq)^QMAC#=(8!b#$;S zWGT75=A;5|Y7N-w$jJRGuod*4rK5EH4*tHK?0!13;^#J zJTw5@azX?LMIrxJgb3EuTe{!41JJUB0Du|If2ur~$GkaA0N{EO^Pa*i@ zEsqD7c>(`wgC`yU^9u0CoAU_FUjB3GgW1V{ex?6kI~p8%)fjNlWCjBkC*SZ=1OK;~ z0T&4jPhLazgMv(B_?PR&jhmVYFpLbJ{219DJ zMx<{b!0dNq-jHs-)sE<)Iu{k~Y zaO*rk|5$UpMzZG9`EYjM3S~a9def=Brvg14DW|fCvq^~b^y2^JXXOUB^o3x&g8!vE zc(r=uAPr4~G0B}dyVU(JW`|~_Pb_@MUkzF9B~}Wehs(lRa570$E!9}mVUNs9Ba3&S znnPHMnVhWetnZB@g@e;d=Y78x!=C@Rn1r~%6f#-lgcmNKtQYHcs7aS^=Q4t``tH8+ zjoJy9SsgzZnefu;ueU$%1PaP@ucCz!n1%%2gN%8@`uzqwe&gn{Ff~kMXKUAZw*C=e zap%p4$gVkcrn&8hZFt9;Hs7y`1?B38o##AmHf(p%w4n+ z`)#>V;q!*dC7qLe_Yy4JVN}y-!09&KrlutQk=#TX+cnwSi+0I)SyCUKnMYkDvyx?4 zR4I69(ib8pm_``svVsEPhSRF&HD%bdn2<)~G8r99uahL4EAFK9fRVZ>cb4`>dk5m- zA^O?TU?S%o_UO9<%A_TqO0x|4?pT!B(cbWgd9_67D`Sfgyd4-slnC%v--a>)Caf~a zg0cMaS=K%;c=g}JH%0b~e$A8rrhbMNADuFM>gYxNzQ7-dMk&GZ;nFe@(?+lo)D`v` zCvTrcn~u;wQB!q|V(M3f;9o)m=QCvts8eT@e|h}?iT8=)s>uSj+50}w#I_(C&DpV| zcA6SybsjEMOpqZ@t0ORQhByWtK0tPS`_ehXp5GsoWR4DIOK(8cHTpYC>fCpUwxRso z)sbY%H;W0Il-$l$w|-zlXCb8b_LdEMpMb4>fTk1yNjHb605dIPqYC)-pR|4bPViw% zA7OtD6M|nYj4~pyLql%qiPuMKW{W@lP9NeF!$+a!(5y_S-waM_US2M;O*#$xorG&} zvh<7r7McVMnZYXOU>bD_FH$xWQGwrho*@i)%lld)lNDcAct(aHDxb86)ugb<8lP|; zrc!qLu3R7*Vp*5&IlzTkjSa7AX*Y$fD2;I1eA8+kIG90{0}5gVwq|X*NU()IvEuYJ z1_nkS|Cy{OxV~6ru##Dpd(B`29ch9uMI?{jq4D&Y^{3`m|B`tBJ}y~u*EFK)-ez7{ z6u78{$(vv@9Vi0?vcMv^rxRC5NrbZZvoncQMzC};Y-}7+c=(}+(>gOK zM?zfEV|oj3&l1`W8~z))lf-A6WQ#DHg$O7TDUn=QKf-V%TRU*3DgiqX>MXA1O)#18 zw;AGinxOfg@N9jt*r2Y+Fe?gb(}V@yP~+4&WTU=1tWyg~h00R$8>FZ}dX z_%hcn+dPzL(lfHz**B^Z)dNU12;A((x^X)k17l7dPI><-7uA<$No^Po8`$JT`qnAq zRSifdD1Mw^3IAFsufb`NywFd#n%6LPJba4f)u))t&0^E3@94^Z>Y<@Ip%wWnq?&3{ zp06V}k?}ci?1+>BWG?X@;qP#HvNRHQt}h!R;uR!|l)Qn(EwK~^FLnlyG~-0Y0y8@v zHp#+hxqGj(QFSQ2Wc-g&al&iLHZ&>L{M<4z>1qt9aX+%y7?S42qURdYc&L5Z*(cF4 zdFHcSRmcqyu}zeJ-?oGlUDIJ^(`g*Cv0{|D`{BHJjQpu75z)(D@8q zSL~|}X!A}!$MwUDv1JX$Ns(4=F3!Tz`-f}&Q)g$lF997@IW-vc`ctIWhru$W8$`Nr z06>Z%RJFYJ=P|-Qt}kW2O%K#9Dm z%c>B1lVaxx@S!mO3<2O)7!d2eVCW?UpPu_Px0ZF1ya_t&o{?jbdj=z;Diu>$9!_Yo54@yjRn(*p$UPg7qv!0~;z!3P0}eJn%3uPy~mFc9bH zCoZV^G@#bdEpU`YjVI@=GFaPK7X_o>I0e)5WUvK}I3c}%go6=BnDPxWJ?QRb8n*~o z%jOJt^g*~Q9&v{Gx@F!a99ZwxPFRZwXW)&LLiAL1i(vwOQ(PYMI*!rz;?lIMDFEMG zz^i>g9)?TVz#S=Pk3aFA=~ns5VleZvNAT`;Qj~q4iM1DQ(*f=4*v2_5`(p6{QVshM zTlbNGv}wBS4J>)u6#`zbZDK3>HCR9_iXs^Rdv_gxVW1CI zu|Nj#K+brPvID12ICswTsg&ubGHC3cUDLleP;0vr;1^--$ubKoWV_t4zN(bXuVXrJ z#gCeGhR^Tr-7SsOyKZdSGP`wh`pKtGm~zDSxk9D?=7Wx#n3n6%(g^U^L&=G)hFbY; z<8X2Vz1!+zV(=_l1^5 z5+zNkCd9s;ou_?Qp7ja7M)$ZobF2PNtEq9&c`aFL5VYgey_L9HGc7hxM|Conb9n1n z&t9#hed=9$u058}BqhcW=XZ|Qc_KZE-An$2v-!kJXPzahlW+GIkjm=l99+4GuSv2r z&aoxuNI|UV8C!5{7FsX@`3$^!oUPRf(Z4Y# z-s7L3;bII{ay;tu)mrNwaKKePylM>;RHwl22iwF)<9?=Ce znQ_?JHaFZ|?`r2sKoTW#+U0}dZa5R3OXS>r>ZMu7{UF9-dQu>QWUOZrDFp=|t()Sh zF`u%Db9%a+gamNU+yAU|=9uH-;7Nd-I&zpE+v+$%KiMWuSIT;B5`VLMj&^cE&q-?oH&9o-UsXcBS>Ox63>{W#**d+@zWXx-*{4c9-)^ zmQBiHGL;E4Qfj-K*_7rpHwz%FiGL0AWM(F)Y*Izw$xB6``ATnZ2_RV_>vJhf+jb+&N;q2x z&T|(lbKan~o*eI{6m$A>#xt|+UFVo!!b|sQg33HdRl2?I7B{!e&3Ps5$(&3i`H^rj zmocL*-5-QPG4shKQz<+%P2x z1?T3GmKrAjA>(;qk@dt?OPEN^$>vNZIdicc&UOPoh?`88_N{Yc0bGm)FrOpB__gvG zM|-vM>D;=QbCmBr$#)6h$#-NUh!+>RfH5*G z`-}uP-S_`EV4Rwqg$TJLVBHoI9W0GkgdGGaI3O}M$e;3QI-?KQQB^W z37Sac41YCj;PD!K%KH=7-F}j^9md!enGHvy74$j*TyQy+8Nb#t&&*P0#we5oYc!+T zR_5j|z$oE$jI7raR?o7Mkjic{He(jP=cVM2+S$zM_+??foB2)?IZ0Ue3Q`~|I;l)o z@SHg-*?D#IkK?x)7SzW#p9KhOb}o@kdJQ!xDp&P6=e^Lr4@V3E+N{@Ywv5KbA~_L&XTHn)HL2Q}n*~rZN2cQuN~y>5#zv{|aIWCcuB|HonI-^v=8Su= z(RCAmt)(6o2=|C9jl^#D$O%8vN*mIAcurLVV(yVekKM=j z$)vHN*nh7$G?OH)Zq}1rm)0|>$?3RcD*1qRA;O6V zbk1n=A=S`L0#KyDW|n4ubtY(A-I>hKbDP~~7v7X(TLor)<}?r zKAGaxz$oj<=H|wYI3s0KHw(bS8SNLsQc5KQnyQ|OmhE-{9J<5ivWAs}1OQ!taN$`toT9PtPjmBTAe<5S zC$!B-WiJY;aOquL08x36%!O4c^CM%<2ue5{JWaZ_Co$3UX})lg`d$-eOy>?F$#^Hvy(z^F0A5;jd)nxs zDqIO*gD^ilRLpq~vpHUN-TNqE@L_Mp(>)4zHy@5}7Jw$EQl6AXQvY2+F0p;K;R+z^?WzwS367TvAUA)s?pF1z=b@l|pSUpr zJPO)#9#xuom`MduU~Xs5>Vng9|R+nkw8ZOADNiMgDlK1yXbMx5aM@MCIz^0r~O3geBg?B_CR38xp{M9|Y8l337Xo5e zGsyfp5symZ98WZncrA1OPe*1hi^iwak~R?>GMZ1#Po8IJY)w(s9MOrivzpu{f$uF- zk=)^T+I1m(32Ad)WYc96N!!pQlUAQFFL}Zxk(X}l0;E(Umvil5t3=8Kk!stFnaLu1 z#*mbem=jDpkfiU*=xV3-wz(PhoblnLOjLnvdQ3T-+(yB1QCCW)p}njzuP1;cV-h)l zE_hqqP66IwS@$r4dUW`Z$yJ=78#PuzDP5RH^xUZU{&S%A!p zL3kCZ57vp2O47Yq5-o${$eGf0##auc3TBqB$jF?j-*1x5A9#s&o&=2qADM<5;F6B} z8lKuYcfmhcA%bnr&zp`)O4soY62QGZ4LD;uC9?UzM)R3dLnCTxn;zSI){9Pm2#}Iv z&SY*p3y?Un+++U9y5IyonWKOwkz;Iy_5gBT#gXNW@QR>r$lgsk!)$D8yjtRB1c5o= z!i-Z0$jLtjMS)9g7qXe{Lc*(zFRIA}cvZ7<$wW3dexBLTXb(4$J17MOnO4iqU@no7 z9mP9t)DntqA9+09;J6%~jgqZ$G|%P=0oqRUcHqWAz>Ia|o|Mm6j>^cnq-+bDTp^nZ zsNQ+iRyUKJYHwuRb9VIEO18jx5;A>fNyf2h-ypc|$;~U<mR&D+b6Iyi9{2sv(f6P5Y-=;)H{{hs?bX$kZ(IoUQ&tlM z*&E(Awv&mUEV?7-3tWn$Z+UzC&OF-%s>F?>oE!*q3K!ly%7qzQQ06nT>@JXFG)*nJ zmtQ61O;0jl+uLF9kzgyYwg(B|-u3~u1;-02CrR5BUP zCQ`HyN?R@W8eZChjmH4S7pIN~*(O)((%x}yJT@?wnxh+Yul~(?!{P9FqSxKbV>;n# z3?M^S=)NlZ*Q7hfAHMlC;Pq9=bS<>7iN~o_CP&KApz1g`8}2yrRrwx3oDrCzHz3r5@ArhaXQq zC0d@jag=jEsqlFBj0@z2vjAX#$MkTZN0WQ)K0PER$M(-aqMvKL*Opi%j@S?!(t#4hi5s zp9*;A5%u$H6Ov(>Im$lFetYllx40j`Z}HcF+3fAT4@dyO2U@vDOn|XC@Bi`OpT4nw z54QjK!-HGh!guR4-+keA{*c*z@K&K8J^10lquY894^u0thu_>s3;%wze?L56W&#ZJ zU0}ls9tEsxzKQ$DDMz<{KfN!11HU8Xx7|syBExO(fYHfP$kpq@ze*eD-FaQg; V6*IoSW*h(j002ovPDHLkV1lnT9^(K2 literal 0 HcmV?d00001 From a67c1ef443a1f89c252874c4904eae519e610fb9 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Mon, 16 Feb 2015 23:39:01 +1300 Subject: [PATCH 15/15] Minor Blackbox doc fix --- docs/Blackbox.md | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/docs/Blackbox.md b/docs/Blackbox.md index d90faa5c8..e7f4b4f1d 100644 --- a/docs/Blackbox.md +++ b/docs/Blackbox.md @@ -105,7 +105,7 @@ baud,escape,esc#,mode,verb,echo,ignoreRX #### Serial port -A 115200 baud serial port is required to connect the OpenLog to your flight controller (such as serial_port_1 on the +A 115200 baud serial port is required to connect the OpenLog to your flight controller (such as `serial_port_1` on the Naze32, the two-pin Tx/Rx header in the center of the board). The Blackbox can not be used with softserial ports as they are too slow. @@ -132,10 +132,11 @@ pressing enter. Now choose the device that you want to log to: ### OpenLog serial data logger Enter `set blackbox_device=0` to switch to logging to a serial port (this is the default). -You then need to let Cleanflight know which of [your serial ports][] you connected the Blackbox to. A 115200 baud port -is required (such as serial_port_1 on the Naze32, the two-pin Tx/Rx header in the center of the board). +You then need to let Cleanflight know which of [your serial ports][] you connected the OpenLog to. A 115200 baud port +is required (such as `serial_port_1` on the Naze32, the two-pin Tx/Rx header in the center of the board). -For example, use `set serial_port_1_scenario=11` to switch the main serial port to MSP, CLI, Blackbox and GPS Passthrough. +For example, use `set serial_port_1_scenario=11` to switch the main serial port to MSP, CLI, Blackbox and GPS +Passthrough. You can also use the GUI to configure a port for the Blackbox feature on the Ports tab. ### Onboard dataflash Enter `set blackbox_device=1` to switch to logging to an onboard dataflash chip, if your flight controller has one.