Skip to content

Commit

Permalink
Merge c179a18 into b147f4e
Browse files Browse the repository at this point in the history
  • Loading branch information
julianoes committed Jul 11, 2019
2 parents b147f4e + c179a18 commit 9dc8d28
Show file tree
Hide file tree
Showing 6 changed files with 91 additions and 84 deletions.
20 changes: 8 additions & 12 deletions src/core/mavlink_parameters.cpp
Expand Up @@ -30,9 +30,9 @@ MAVLinkParameters::~MAVLinkParameters()

void MAVLinkParameters::set_param_async(const std::string &name,
const ParamValue &value,
set_param_callback_t callback,
const void *cookie,
bool extended)
bool extended,
set_param_callback_t callback)
{
// if (value.is_float()) {
// LogDebug() << "setting param " << name << " to " << value.get_float();
Expand Down Expand Up @@ -66,16 +66,16 @@ MAVLinkParameters::set_param(const std::string &name, const ParamValue &value, b
auto res = prom.get_future();

set_param_async(
name, value, [&prom](Result result) { prom.set_value(result); }, this, extended);
name, value, this, extended, [&prom](Result result) { prom.set_value(result); });

return res.get();
}

void MAVLinkParameters::get_param_async(const std::string &name,
ParamValue value_type,
get_param_callback_t callback,
const void *cookie,
bool extended)
bool extended,
get_param_callback_t callback)
{
// LogDebug() << "getting param " << name << ", extended: " << (extended ? "yes" : "no");

Expand Down Expand Up @@ -114,13 +114,9 @@ MAVLinkParameters::get_param(const std::string &name, ParamValue value_type, boo
auto prom = std::promise<std::pair<Result, MAVLinkParameters::ParamValue>>();
auto res = prom.get_future();

get_param_async(name,
value_type,
[&prom](Result result, ParamValue value) {
prom.set_value(std::make_pair<>(result, value));
},
this,
extended);
get_param_async(name, value_type, this, extended, [&prom](Result result, ParamValue value) {
prom.set_value(std::make_pair<>(result, value));
});

return res.get();
}
Expand Down
10 changes: 5 additions & 5 deletions src/core/mavlink_parameters.h
Expand Up @@ -483,18 +483,18 @@ class MAVLinkParameters {

void set_param_async(const std::string &name,
const ParamValue &value,
set_param_callback_t callback,
const void *cookie = nullptr,
bool extended = false);
const void *cookie,
bool extended,
set_param_callback_t callback);

std::pair<Result, ParamValue>
get_param(const std::string &name, ParamValue value_type, bool extended);
typedef std::function<void(Result, ParamValue value)> get_param_callback_t;
void get_param_async(const std::string &name,
ParamValue value_type,
get_param_callback_t callback,
const void *cookie,
bool extended = false);
bool extended,
get_param_callback_t callback);

void cancel_all_param(const void *cookie);

Expand Down
64 changes: 36 additions & 28 deletions src/core/system_impl.cpp
Expand Up @@ -676,7 +676,7 @@ void SystemImpl::set_param_float_async(const std::string &name,
{
MAVLinkParameters::ParamValue param_value;
param_value.set_float(value);
_params.set_param_async(name, param_value, callback, cookie);
_params.set_param_async(name, param_value, cookie, false, callback);
}

void SystemImpl::set_param_int_async(const std::string &name,
Expand All @@ -686,7 +686,7 @@ void SystemImpl::set_param_int_async(const std::string &name,
{
MAVLinkParameters::ParamValue param_value;
param_value.set_int32(value);
_params.set_param_async(name, param_value, callback, cookie);
_params.set_param_async(name, param_value, cookie, false, callback);
}

void SystemImpl::set_param_ext_float_async(const std::string &name,
Expand All @@ -696,7 +696,7 @@ void SystemImpl::set_param_ext_float_async(const std::string &name,
{
MAVLinkParameters::ParamValue param_value;
param_value.set_float(value);
_params.set_param_async(name, param_value, callback, cookie, true);
_params.set_param_async(name, param_value, cookie, true, callback);
}

void SystemImpl::set_param_ext_int_async(const std::string &name,
Expand All @@ -706,7 +706,7 @@ void SystemImpl::set_param_ext_int_async(const std::string &name,
{
MAVLinkParameters::ParamValue param_value;
param_value.set_int32(value);
_params.set_param_async(name, param_value, callback, cookie, true);
_params.set_param_async(name, param_value, cookie, true, callback);
}

std::pair<MAVLinkParameters::Result, float> SystemImpl::get_param_float(const std::string &name)
Expand All @@ -720,14 +720,15 @@ std::pair<MAVLinkParameters::Result, float> SystemImpl::get_param_float(const st
_params.get_param_async(
name,
value_type,
this,
false,
[&prom](MAVLinkParameters::Result result, MAVLinkParameters::ParamValue param) {
float value = NAN;
if (result == MAVLinkParameters::Result::SUCCESS) {
value = param.get_float();
}
prom.set_value(std::make_pair<>(result, value));
},
this);
});

return res.get();
}
Expand All @@ -743,14 +744,15 @@ std::pair<MAVLinkParameters::Result, int> SystemImpl::get_param_int(const std::s
_params.get_param_async(
name,
value_type,
this,
false,
[&prom](MAVLinkParameters::Result result, MAVLinkParameters::ParamValue param) {
int value = 0;
if (result == MAVLinkParameters::Result::SUCCESS) {
value = param.get_int32();
}
prom.set_value(std::make_pair<>(result, value));
},
this);
});

return res.get();
}
Expand All @@ -766,15 +768,15 @@ std::pair<MAVLinkParameters::Result, float> SystemImpl::get_param_ext_float(cons
_params.get_param_async(
name,
value_type,
this,
true,
[&prom](MAVLinkParameters::Result result, MAVLinkParameters::ParamValue param) {
float value = NAN;
if (result == MAVLinkParameters::Result::SUCCESS) {
value = param.get_float();
}
prom.set_value(std::make_pair<>(result, value));
},
this,
true);
});

return res.get();
}
Expand All @@ -790,15 +792,15 @@ std::pair<MAVLinkParameters::Result, int> SystemImpl::get_param_ext_int(const st
_params.get_param_async(
name,
value_type,
this,
true,
[&prom](MAVLinkParameters::Result result, MAVLinkParameters::ParamValue param) {
int value = 0;
if (result == MAVLinkParameters::Result::SUCCESS) {
value = param.get_int32();
}
prom.set_value(std::make_pair<>(result, value));
},
this,
true);
});

return res.get();
}
Expand All @@ -810,8 +812,11 @@ void SystemImpl::get_param_float_async(const std::string &name,
MAVLinkParameters::ParamValue value_type;
value_type.set_float(0.0f);

_params.get_param_async(
name, value_type, std::bind(&SystemImpl::receive_float_param, _1, _2, callback), cookie);
_params.get_param_async(name,
value_type,
cookie,
false,
std::bind(&SystemImpl::receive_float_param, _1, _2, callback));
}

void SystemImpl::get_param_int_async(const std::string &name,
Expand All @@ -821,8 +826,11 @@ void SystemImpl::get_param_int_async(const std::string &name,
MAVLinkParameters::ParamValue value_type;
value_type.set_int32(0);

_params.get_param_async(
name, value_type, std::bind(&SystemImpl::receive_int_param, _1, _2, callback), cookie);
_params.get_param_async(name,
value_type,
cookie,
false,
std::bind(&SystemImpl::receive_int_param, _1, _2, callback));
}

void SystemImpl::get_param_ext_float_async(const std::string &name,
Expand All @@ -834,9 +842,9 @@ void SystemImpl::get_param_ext_float_async(const std::string &name,

_params.get_param_async(name,
value_type,
std::bind(&SystemImpl::receive_float_param, _1, _2, callback),
cookie,
true);
true,
std::bind(&SystemImpl::receive_float_param, _1, _2, callback));
}

void SystemImpl::get_param_ext_int_async(const std::string &name,
Expand All @@ -848,18 +856,18 @@ void SystemImpl::get_param_ext_int_async(const std::string &name,

_params.get_param_async(name,
value_type,
std::bind(&SystemImpl::receive_int_param, _1, _2, callback),
cookie,
true);
true,
std::bind(&SystemImpl::receive_int_param, _1, _2, callback));
}

void SystemImpl::set_param_async(const std::string &name,
MAVLinkParameters::ParamValue value,
success_t callback,
const void *cookie,
bool extended)
bool extended,
success_t callback)
{
_params.set_param_async(name, value, callback, cookie, extended);
_params.set_param_async(name, value, cookie, extended, callback);
}

MAVLinkParameters::Result
Expand All @@ -870,11 +878,11 @@ SystemImpl::set_param(const std::string &name, MAVLinkParameters::ParamValue val

void SystemImpl::get_param_async(const std::string &name,
MAVLinkParameters::ParamValue value_type,
get_param_callback_t callback,
const void *cookie,
bool extended)
bool extended,
get_param_callback_t callback)
{
_params.get_param_async(name, value_type, callback, cookie, extended);
_params.get_param_async(name, value_type, cookie, extended, callback);
}

void SystemImpl::cancel_all_param(const void *cookie)
Expand Down
8 changes: 4 additions & 4 deletions src/core/system_impl.h
Expand Up @@ -173,18 +173,18 @@ class SystemImpl {

void set_param_async(const std::string &name,
MAVLinkParameters::ParamValue value,
success_t callback,
const void *cookie,
bool extended = false);
bool extended,
success_t callback);

MAVLinkParameters::Result
set_param(const std::string &name, MAVLinkParameters::ParamValue value, bool extended = false);

void get_param_async(const std::string &name,
MAVLinkParameters::ParamValue value_type,
get_param_callback_t callback,
const void *cookie,
bool extended);
bool extended,
get_param_callback_t callback);

void cancel_all_param(const void *cookie);

Expand Down
12 changes: 6 additions & 6 deletions src/plugins/camera/camera_impl.cpp
Expand Up @@ -1240,6 +1240,8 @@ void CameraImpl::set_option_async(const std::string &setting_id,

_parent->set_param_async(setting_id,
value,
this,
true,
[this, callback, setting_id, value](MAVLinkParameters::Result result) {
if (result == MAVLinkParameters::Result::SUCCESS) {
if (this->_camera_definition) {
Expand All @@ -1254,9 +1256,7 @@ void CameraImpl::set_option_async(const std::string &setting_id,
callback(Camera::Result::ERROR);
}
}
},
this,
true);
});
}

Camera::Result CameraImpl::get_option(const std::string &setting_id, Camera::Option &option)
Expand Down Expand Up @@ -1438,6 +1438,8 @@ void CameraImpl::refresh_params()
const bool is_last = (count + 1 == params.size());
_parent->get_param_async(param_name,
param_value_type,
this,
true,
[param_name, is_last, this](MAVLinkParameters::Result result,
MAVLinkParameters::ParamValue value) {
if (result != MAVLinkParameters::Result::SUCCESS) {
Expand All @@ -1453,9 +1455,7 @@ void CameraImpl::refresh_params()
notify_current_settings();
notify_possible_setting_options();
}
},
this,
true);
});
++count;
}
}
Expand Down
61 changes: 32 additions & 29 deletions src/plugins/follow_me/follow_me_impl.cpp
Expand Up @@ -34,35 +34,38 @@ void FollowMeImpl::deinit()

void FollowMeImpl::enable()
{
_parent->get_param_float_async("NAV_MIN_FT_HT",
[this](MAVLinkParameters::Result result, float value) {
if (result == MAVLinkParameters::Result::SUCCESS) {
_config.min_height_m = value;
}
},
this);
_parent->get_param_float_async("NAV_FT_DST",
[this](MAVLinkParameters::Result result, float value) {
if (result == MAVLinkParameters::Result::SUCCESS) {
_config.follow_distance_m = value;
}
},
this);
_parent->get_param_int_async("NAV_FT_FS",
[this](MAVLinkParameters::Result result, int32_t value) {
if (result == MAVLinkParameters::Result::SUCCESS) {
_config.follow_direction =
static_cast<FollowMe::Config::FollowDirection>(value);
}
},
this);
_parent->get_param_float_async("NAV_FT_RS",
[this](MAVLinkParameters::Result result, float value) {
if (result == MAVLinkParameters::Result::SUCCESS) {
_config.responsiveness = value;
}
},
this);
_parent->get_param_float_async(
"NAV_MIN_FT_HT",
[this](MAVLinkParameters::Result result, float value) {
if (result == MAVLinkParameters::Result::SUCCESS) {
_config.min_height_m = value;
}
},
this);
_parent->get_param_float_async(
"NAV_FT_DST",
[this](MAVLinkParameters::Result result, float value) {
if (result == MAVLinkParameters::Result::SUCCESS) {
_config.follow_distance_m = value;
}
},
this);
_parent->get_param_int_async(
"NAV_FT_FS",
[this](MAVLinkParameters::Result result, int32_t value) {
if (result == MAVLinkParameters::Result::SUCCESS) {
_config.follow_direction = static_cast<FollowMe::Config::FollowDirection>(value);
}
},
this);
_parent->get_param_float_async(
"NAV_FT_RS",
[this](MAVLinkParameters::Result result, float value) {
if (result == MAVLinkParameters::Result::SUCCESS) {
_config.responsiveness = value;
}
},
this);
}

void FollowMeImpl::disable()
Expand Down

0 comments on commit 9dc8d28

Please sign in to comment.