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

Remove caching in params #847

Merged
merged 3 commits into from
Sep 12, 2019
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.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
28 changes: 0 additions & 28 deletions src/core/mavlink_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,14 +90,6 @@ void MAVLinkParameters::get_param_async(
return;
}

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

// Otherwise push work onto queue.
WorkItem new_work{};
new_work.type = WorkItem::Type::Get;
Expand Down Expand Up @@ -259,20 +251,6 @@ void MAVLinkParameters::do_work()
}
}

void MAVLinkParameters::remove_from_cache(const std::string& name)
{
const auto& it = _cache.find(name);
if (it == _cache.end()) {
return;
}
_cache.erase(it);
}

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

void MAVLinkParameters::process_param_value(const mavlink_message_t& message)
{
mavlink_param_value_t param_value;
Expand Down Expand Up @@ -301,7 +279,6 @@ void MAVLinkParameters::process_param_value(const mavlink_message_t& message)
ParamValue value;
value.set_from_mavlink_param_value(param_value);
if (value.is_same_type(work->param_value)) {
_cache[work->param_name] = value;
if (work->get_param_callback) {
work->get_param_callback(MAVLinkParameters::Result::SUCCESS, value);
}
Expand All @@ -319,7 +296,6 @@ void MAVLinkParameters::process_param_value(const mavlink_message_t& message)
} break;
case WorkItem::Type::Set: {
// We are done, inform caller and go back to idle
_cache[work->param_name] = work->param_value;
if (work->set_param_callback) {
work->set_param_callback(MAVLinkParameters::Result::SUCCESS);
}
Expand Down Expand Up @@ -359,15 +335,13 @@ void MAVLinkParameters::process_param_ext_value(const mavlink_message_t& message
ParamValue value;
value.set_from_mavlink_param_ext_value(param_ext_value);
if (value.is_same_type(work->param_value)) {
_cache[work->param_name] = value;
if (work->get_param_callback) {
work->get_param_callback(MAVLinkParameters::Result::SUCCESS, value);
}
} else if (value.is_uint8() && work->param_value.is_uint16()) {
// FIXME: workaround for mismatching type uint8_t which should be uint16_t.
ParamValue correct_type_value;
correct_type_value.set_uint16(static_cast<uint16_t>(value.get_uint8()));
_cache[work->param_name] = correct_type_value;
if (work->get_param_callback) {
work->get_param_callback(
MAVLinkParameters::Result::SUCCESS, correct_type_value);
Expand All @@ -376,7 +350,6 @@ void MAVLinkParameters::process_param_ext_value(const mavlink_message_t& message
// FIXME: workaround for mismatching type uint8_t which should be uint32_t.
ParamValue correct_type_value;
correct_type_value.set_uint32(static_cast<uint32_t>(value.get_uint8()));
_cache[work->param_name] = correct_type_value;
if (work->get_param_callback) {
work->get_param_callback(
MAVLinkParameters::Result::SUCCESS, correct_type_value);
Expand Down Expand Up @@ -431,7 +404,6 @@ void MAVLinkParameters::process_param_ext_ack(const mavlink_message_t& message)
case WorkItem::Type::Set: {
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->set_param_callback) {
work->set_param_callback(MAVLinkParameters::Result::SUCCESS);
}
Expand Down
5 changes: 0 additions & 5 deletions src/core/mavlink_parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -605,9 +605,6 @@ class MAVLinkParameters {

void do_work();

void reset_cache();
void remove_from_cache(const std::string& name);

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

// Non-copyable
Expand Down Expand Up @@ -641,8 +638,6 @@ class MAVLinkParameters {
};
LockedQueue<WorkItem> _work_queue{};

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

void* _timeout_cookie = nullptr;

// dl_time_t _last_request_time = {};
Expand Down
2 changes: 0 additions & 2 deletions src/core/system_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1143,8 +1143,6 @@ void SystemImpl::call_user_callback(const std::function<void()>& func)

void SystemImpl::param_changed(const std::string& name)
{
_params.remove_from_cache(name);

std::lock_guard<std::mutex> lock(_param_changed_callbacks_mutex);

for (auto& callback : _param_changed_callbacks) {
Expand Down