Skip to content
This repository has been archived by the owner on May 9, 2019. It is now read-only.

Commit

Permalink
refs #45 Tweak buffer sizes and things.
Browse files Browse the repository at this point in the history
  • Loading branch information
yoos committed Jun 17, 2015
1 parent 6e8afe5 commit 42771be
Show file tree
Hide file tree
Showing 6 changed files with 32 additions and 28 deletions.
14 changes: 9 additions & 5 deletions src/filesystem/filesystem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -137,18 +137,22 @@ void FileSystem::write(uint8_t *buf, uint16_t len) {
// TODO(yoos): set FS error flag
//chprintf(chp, "write failed\r\n");
}
err = f_sync(&FileObject); // TODO(yoos): This ensures data gets written, but bad for performance...
if (err != FR_OK) {
// TODO(yoos): set FS error flag
//chprintf(chp, "sync failed\r\n");
}
if (bytes_written != len) {
// TODO(yoos): set FS error flag
//chprintf(chp, "write incomplete\r\n");
}
//sync(); // TODO(yoos): This ensures data gets written, but bad for performance...
// TODO(yoos): On failure, reset logger to wait state
}

void FileSystem::sync(void) {
err = f_sync(&FileObject);
if (err != FR_OK) {
// TODO(yoos): set FS error flag
//chprintf(chp, "sync failed\r\n");
}
}

void FileSystem::getFn(char *buf) {
std::strcpy(buf, fname);
}
Expand Down
5 changes: 5 additions & 0 deletions src/filesystem/filesystem.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,11 @@ class FileSystem {
*/
void write(uint8_t *c, uint16_t len);

/**
* Sync filesystem.
*/
void sync(void);

/**
* Get short filename
*/
Expand Down
19 changes: 7 additions & 12 deletions src/filesystem/fs_writer_thread.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
FsWriterThread::FsWriterThread(SDCDriver& sdcd, Communicator& communicator)
: fs(sdcd),
fsInfoMessageStream(communicator, 1) {
rb_init(&buf, sizeof(_buf), _buf);
}

msg_t FsWriterThread::main() {
Expand All @@ -17,19 +18,14 @@ msg_t FsWriterThread::main() {
while (!fs.connect()) chThdSleepMilliseconds(10);
while (!fs.mount()) chThdSleepMilliseconds(10);
while (!fs.openNew()) chThdSleepMilliseconds(10);
fsReady = true;

while(true) {
// Check if there is data in the buffer that has not yet been written.
if(bottom != top) {
size_t numbytes = (top > bottom) ? top-bottom : buffer.size()-bottom;
fs.write(&buffer[bottom], numbytes);
bottom += numbytes;

// Wrap if the end of the buffer is reached.
if(bottom >= buffer.size()) {
bottom = 0;
}
}
uint32_t count = buf.count;
if (count > 3000) count = 3000 + 0.0625*(count-3000);
rb_remove(&buf, count, writebuf);
fs.write(writebuf, count);
fs.sync();

if (fsInfoMessageStream.ready()) {
protocol::message::fs_info_message_t m;
Expand All @@ -40,7 +36,6 @@ msg_t FsWriterThread::main() {
fsInfoMessageStream.publish(m);
}

// TODO(kyle): Just yield, or sleep?
yield();
}

Expand Down
10 changes: 6 additions & 4 deletions src/filesystem/fs_writer_thread.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,11 +9,12 @@
#include "communication/communicator.hpp"
#include "communication/rate_limited_stream.hpp"
#include "filesystem/filesystem.hpp"
#include "filesystem/ringbuffer.hpp"

/**
* Thread to write to storage media without blocking control thread.
*/
class FsWriterThread : public chibios_rt::BaseStaticThread<2048> {
class FsWriterThread : public chibios_rt::BaseStaticThread<1024> {
public:
FsWriterThread(SDCDriver& sdcd, Communicator& communicator);

Expand All @@ -27,11 +28,12 @@ class FsWriterThread : public chibios_rt::BaseStaticThread<2048> {

private:
FileSystem fs;
bool fsReady;
RateLimitedStream fsInfoMessageStream;

std::array<std::uint8_t, 20000> buffer;
std::size_t bottom;
std::size_t top;
rb_t buf;
std::uint8_t _buf[83000];
std::uint8_t writebuf[8000];
};

#include "filesystem/fs_writer_thread.tpp"
Expand Down
10 changes: 4 additions & 6 deletions src/filesystem/fs_writer_thread.tpp
Original file line number Diff line number Diff line change
@@ -1,10 +1,8 @@
#include <chprintf.h>

template <std::size_t size>
void FsWriterThread::append(std::array<std::uint8_t, size> ap, std::size_t len) {
for(std::size_t i = 0; i < len; i++) {
buffer[top++] = ap[i];

if(top >= buffer.size()) {
top = 0;
}
if (fsReady) {
rb_add(&buf, len, ap.data());
}
}
2 changes: 1 addition & 1 deletion src/filesystem/logger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ void Logger::start(void) {
// TODO(yoos): Rethink this, as in the rocket, we really want to log data
// before we transmit to ground, but this is not the case in radio-controlled
// vehicles. Maybe priorities should be user-configurable.
writer.start(LOWPRIO + 2);
writer.start(HIGHPRIO-1);
}

bool Logger::ready(void) {
Expand Down

0 comments on commit 42771be

Please sign in to comment.