Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Use semaphore to mediate access to DataFlash-over-MAVLink #6003

Merged
merged 2 commits into from Apr 6, 2017
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
25 changes: 22 additions & 3 deletions libraries/DataFlash/DataFlash_MAVLink.cpp
Expand Up @@ -25,6 +25,12 @@ extern const AP_HAL::HAL& hal;
// initialisation
void DataFlash_MAVLink::Init()
{
semaphore = hal.util->new_semaphore();
if (semaphore == nullptr) {
AP_HAL::panic("Failed to create DataFlash_MAVLink semaphore");
return;
}

DataFlash_Backend::Init();

_blocks = nullptr;
Expand Down Expand Up @@ -121,7 +127,13 @@ bool DataFlash_MAVLink::WritePrioritisedBlock(const void *pBuffer, uint16_t size
return false;
}

if (!semaphore->take_nonblocking()) {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Do we really want to use non-blocking take? Would it be so bad to use it with a 10ms timeout?

dropped++;
return false;
}

if (! WriteBlockCheckStartupMessages()) {
semaphore->give();
return false;
}

Expand All @@ -130,6 +142,7 @@ bool DataFlash_MAVLink::WritePrioritisedBlock(const void *pBuffer, uint16_t size
// do not count the startup packets as being dropped...
dropped++;
}
semaphore->give();
return false;
}

Expand All @@ -141,6 +154,7 @@ bool DataFlash_MAVLink::WritePrioritisedBlock(const void *pBuffer, uint16_t size
if (_current_block == nullptr) {
// should not happen - there's a sanity check above
internal_error();
semaphore->give();
return false;
}
}
Expand All @@ -157,9 +171,7 @@ bool DataFlash_MAVLink::WritePrioritisedBlock(const void *pBuffer, uint16_t size
}
}

if (!_writing_startup_messages) {
// push_log_blocks();
}
semaphore->give();

return true;
}
Expand Down Expand Up @@ -465,13 +477,20 @@ void DataFlash_MAVLink::push_log_blocks()

DataFlash_Backend::WriteMoreStartupMessages();

if (!semaphore->take_nonblocking()) {
return;
}

if (! send_log_blocks_from_queue(_blocks_retry)) {
semaphore->give();
return;
}

if (! send_log_blocks_from_queue(_blocks_pending)) {
semaphore->give();
return;
}
semaphore->give();
}

void DataFlash_MAVLink::do_resends(uint32_t now)
Expand Down
11 changes: 8 additions & 3 deletions libraries/DataFlash/DataFlash_MAVLink.h
Expand Up @@ -64,19 +64,23 @@ class DataFlash_MAVLink : public DataFlash_Backend
void ShowDeviceInfo(AP_HAL::BetterStream *port) override {}
void ListAvailableLogs(AP_HAL::BetterStream *port) override {}

void push_log_blocks() override;

void remote_log_block_status_msg(mavlink_channel_t chan, mavlink_message_t* msg) override;

private:

struct dm_block {
uint32_t seqno;
uint8_t buf[MAVLINK_MSG_REMOTE_LOG_DATA_BLOCK_FIELD_DATA_LEN];
uint32_t last_sent;
struct dm_block *next;
};
void push_log_blocks();
bool send_log_block(struct dm_block &block);
void handle_ack(mavlink_channel_t chan, mavlink_message_t* msg, uint32_t seqno);
void handle_retry(uint32_t block_num);
void do_resends(uint32_t now);
void set_channel(mavlink_channel_t chan);
void remote_log_block_status_msg(mavlink_channel_t chan, mavlink_message_t* msg) override;
void free_all_blocks();

// a stack for free blocks, queues for pending, sent, retries and sent
Expand All @@ -99,7 +103,6 @@ class DataFlash_MAVLink : public DataFlash_Backend
dm_block_queue_t _blocks_pending;
dm_block_queue_t _blocks_retry;

protected:
struct _stats {
// the following are reset any time we log stats (see "reset_stats")
uint32_t resends;
Expand Down Expand Up @@ -184,6 +187,8 @@ class DataFlash_MAVLink : public DataFlash_Backend
AP_HAL::Util::perf_counter_t _perf_errors;
AP_HAL::Util::perf_counter_t _perf_packing;
AP_HAL::Util::perf_counter_t _perf_overruns;

AP_HAL::Semaphore *semaphore;
};

#endif // DATAFLASH_MAVLINK_SUPPORT