Skip to content

Commit

Permalink
mavlink_parameters: added param cache
Browse files Browse the repository at this point in the history
This adds a cache for the params so that when you want to get a
parameter, it takes it from the cache if you have received it before.

This will only really be beneficial once plugins can require params
right when they are instantiated respectively when a vehicle is
connected.
  • Loading branch information
julianoes committed Jul 10, 2018
1 parent fb26637 commit 7807616
Show file tree
Hide file tree
Showing 2 changed files with 28 additions and 4 deletions.
27 changes: 23 additions & 4 deletions core/mavlink_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,15 @@ void MAVLinkParameters::get_param_async(const std::string &name,
return;
}

// Use cached value if available.
if (_cache.find(name) != _cache.end()) {
if (callback) {
callback(true, _cache[name]);
}
return;
}

// Otherwise push work onto queue.
GetParamWork new_work;
new_work.callback = callback;
new_work.param_name = name;
Expand Down Expand Up @@ -208,6 +217,11 @@ void MAVLinkParameters::do_work()
}
}

void MAVLinkParameters::reset_cache()
{
_cache.clear();
}

void MAVLinkParameters::process_param_value(const mavlink_message_t &message)
{
// LogDebug() << "getting param value";
Expand All @@ -225,9 +239,10 @@ void MAVLinkParameters::process_param_value(const mavlink_message_t &message)
auto work = _get_param_queue.borrow_front();
if (work) {
if (strncmp(work->param_name.c_str(), param_value.param_id, PARAM_ID_LEN) == 0) {
ParamValue value;
value.set_from_mavlink_param_value(param_value);
_cache[work->param_name] = value;
if (work->callback) {
ParamValue value;
value.set_from_mavlink_param_value(param_value);
work->callback(true, value);
}
_state = State::NONE;
Expand All @@ -248,6 +263,7 @@ void MAVLinkParameters::process_param_value(const mavlink_message_t &message)
// Now it still needs to match the param name
if (strncmp(work->param_name.c_str(), param_value.param_id, PARAM_ID_LEN) == 0) {
// We are done, inform caller and go back to idle
_cache[work->param_name] = work->param_value;
if (work->callback) {
work->callback(true);
}
Expand Down Expand Up @@ -280,9 +296,10 @@ void MAVLinkParameters::process_param_ext_value(const mavlink_message_t &message
auto work = _get_param_queue.borrow_front();
if (work) {
if (strncmp(work->param_name.c_str(), param_ext_value.param_id, PARAM_ID_LEN) == 0) {
ParamValue value;
value.set_from_mavlink_param_ext_value(param_ext_value);
_cache[work->param_name] = value;
if (work->callback) {
ParamValue value;
value.set_from_mavlink_param_ext_value(param_ext_value);
work->callback(true, value);
}
_state = State::NONE;
Expand All @@ -305,6 +322,7 @@ void MAVLinkParameters::process_param_ext_value(const mavlink_message_t &message
if (strncmp(work->param_name.c_str(), param_ext_value.param_id, PARAM_ID_LEN) == 0) {

// We are done, inform caller and go back to idle
_cache[work->param_name] = work->param_value;
if (work->callback) {
work->callback(true);
}
Expand Down Expand Up @@ -340,6 +358,7 @@ void MAVLinkParameters::process_param_ext_ack(const mavlink_message_t &message)
if (strncmp(work->param_name.c_str(), param_ext_ack.param_id, PARAM_ID_LEN) == 0) {
if (param_ext_ack.param_result == PARAM_ACK_ACCEPTED) {
// We are done, inform caller and go back to idle
_cache[work->param_name] = work->param_value;
if (work->callback) {
work->callback(true);
}
Expand Down
5 changes: 5 additions & 0 deletions core/mavlink_parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
#include <functional>
#include <cstring> // for memcpy
#include <cassert>
#include <map>

namespace dronecode_sdk {

Expand Down Expand Up @@ -447,6 +448,8 @@ class MAVLinkParameters {

void do_work();

void reset_cache();

friend std::ostream &operator<<(std::ostream &, const ParamValue &);

// Non-copyable
Expand Down Expand Up @@ -486,6 +489,8 @@ class MAVLinkParameters {
};
LockedQueue<GetParamWork> _get_param_queue{};

std::map<std::string, ParamValue> _cache{};

void *_timeout_cookie = nullptr;

// dl_time_t _last_request_time = {};
Expand Down

0 comments on commit 7807616

Please sign in to comment.