Skip to content

Commit

Permalink
fix style with clang-format 6 (clang-format 8 having a bug)
Browse files Browse the repository at this point in the history
  • Loading branch information
JonasVautherin committed May 4, 2019
1 parent 06969a8 commit 93bd11e
Show file tree
Hide file tree
Showing 3 changed files with 75 additions and 81 deletions.
15 changes: 7 additions & 8 deletions core/mavlink_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -114,14 +114,13 @@ 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,
[&prom](Result result, ParamValue value) {
prom.set_value(std::make_pair<>(result, value));
},
this,
extended);

return res.get();
}
Expand Down
80 changes: 39 additions & 41 deletions plugins/camera/camera_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1259,26 +1259,25 @@ void CameraImpl::set_option_async(const std::string &setting_id,
return;
}

_parent->set_param_async(
setting_id,
value,
[this, callback, setting_id, value](MAVLinkParameters::Result result) {
if (result == MAVLinkParameters::Result::SUCCESS) {
if (this->_camera_definition) {
_camera_definition->set_setting(setting_id, value);
refresh_params();
}
if (callback) {
callback(Camera::Result::SUCCESS);
}
} else {
if (callback) {
callback(Camera::Result::ERROR);
}
}
},
this,
true);
_parent->set_param_async(setting_id,
value,
[this, callback, setting_id, value](MAVLinkParameters::Result result) {
if (result == MAVLinkParameters::Result::SUCCESS) {
if (this->_camera_definition) {
_camera_definition->set_setting(setting_id, value);
refresh_params();
}
if (callback) {
callback(Camera::Result::SUCCESS);
}
} else {
if (callback) {
callback(Camera::Result::ERROR);
}
}
},
this,
true);
}

Camera::Result CameraImpl::get_option(const std::string &setting_id, Camera::Option &option)
Expand Down Expand Up @@ -1458,27 +1457,26 @@ void CameraImpl::refresh_params()
const std::string &param_name = param.first;
const MAVLinkParameters::ParamValue &param_value_type = param.second;
const bool is_last = (count + 1 == params.size());
_parent->get_param_async(
param_name,
param_value_type,
[param_name, is_last, this](MAVLinkParameters::Result result,
MAVLinkParameters::ParamValue value) {
if (result != MAVLinkParameters::Result::SUCCESS) {
return;
}
// We need to check again by the time this callback runs
if (!this->_camera_definition) {
return;
}
this->_camera_definition->set_setting(param_name, value);

if (is_last) {
notify_current_settings();
notify_possible_setting_options();
}
},
this,
true);
_parent->get_param_async(param_name,
param_value_type,
[param_name, is_last, this](MAVLinkParameters::Result result,
MAVLinkParameters::ParamValue value) {
if (result != MAVLinkParameters::Result::SUCCESS) {
return;
}
// We need to check again by the time this callback runs
if (!this->_camera_definition) {
return;
}
this->_camera_definition->set_setting(param_name, value);

if (is_last) {
notify_current_settings();
notify_possible_setting_options();
}
},
this,
true);
++count;
}
}
Expand Down
61 changes: 29 additions & 32 deletions plugins/follow_me/follow_me_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,38 +34,35 @@ 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 93bd11e

Please sign in to comment.