Skip to content

Commit

Permalink
Fix style errors.
Browse files Browse the repository at this point in the history
  • Loading branch information
cswkim authored and JonasVautherin committed May 4, 2019
1 parent 76d5059 commit 06969a8
Show file tree
Hide file tree
Showing 6 changed files with 109 additions and 112 deletions.
24 changes: 12 additions & 12 deletions backend/src/plugins/offboard/offboard_service_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -72,8 +72,8 @@ class OffboardServiceImpl final : public rpc::offboard::OffboardService::Service
return grpc::Status::OK;
}

static dronecode_sdk::Offboard::AttitudeRate translateRPCAttitudeRate(
const rpc::offboard::AttitudeRate &rpc_attitude_rate)
static dronecode_sdk::Offboard::AttitudeRate
translateRPCAttitudeRate(const rpc::offboard::AttitudeRate &rpc_attitude_rate)
{
dronecode_sdk::Offboard::AttitudeRate attitude_rate;

Expand All @@ -90,16 +90,16 @@ class OffboardServiceImpl final : public rpc::offboard::OffboardService::Service
rpc::offboard::SetPositionNedResponse * /* response */) override
{
if (request != nullptr) {
auto requested_position_ned_yaw = translateRPCPositionNEDYaw(
request->position_ned_yaw());
auto requested_position_ned_yaw =
translateRPCPositionNEDYaw(request->position_ned_yaw());
_offboard.set_position_ned(requested_position_ned_yaw);
}

return grpc::Status::OK;
}

static dronecode_sdk::Offboard::PositionNEDYaw translateRPCPositionNEDYaw(
const rpc::offboard::PositionNEDYaw &rpc_position_ned_yaw)
static dronecode_sdk::Offboard::PositionNEDYaw
translateRPCPositionNEDYaw(const rpc::offboard::PositionNEDYaw &rpc_position_ned_yaw)
{
dronecode_sdk::Offboard::PositionNEDYaw position_ned_yaw;

Expand All @@ -116,8 +116,8 @@ class OffboardServiceImpl final : public rpc::offboard::OffboardService::Service
rpc::offboard::SetVelocityBodyResponse * /* response */) override
{
if (request != nullptr) {
auto requested_velocity_body_yawspeed = translateRPCVelocityBodyYawspeed(
request->velocity_body_yawspeed());
auto requested_velocity_body_yawspeed =
translateRPCVelocityBodyYawspeed(request->velocity_body_yawspeed());
_offboard.set_velocity_body(requested_velocity_body_yawspeed);
}

Expand All @@ -142,16 +142,16 @@ class OffboardServiceImpl final : public rpc::offboard::OffboardService::Service
rpc::offboard::SetVelocityNedResponse * /* response */) override
{
if (request != nullptr) {
auto requested_velocity_ned_yaw = translateRPCVelocityNEDYaw(
request->velocity_ned_yaw());
auto requested_velocity_ned_yaw =
translateRPCVelocityNEDYaw(request->velocity_ned_yaw());
_offboard.set_velocity_ned(requested_velocity_ned_yaw);
}

return grpc::Status::OK;
}

static dronecode_sdk::Offboard::VelocityNEDYaw translateRPCVelocityNEDYaw(
const rpc::offboard::VelocityNEDYaw &rpc_velocity_ned_yaw)
static dronecode_sdk::Offboard::VelocityNEDYaw
translateRPCVelocityNEDYaw(const rpc::offboard::VelocityNEDYaw &rpc_velocity_ned_yaw)
{
dronecode_sdk::Offboard::VelocityNEDYaw velocity_ned_yaw;

Expand Down
15 changes: 8 additions & 7 deletions core/mavlink_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -114,13 +114,14 @@ 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: 41 additions & 39 deletions plugins/camera/camera_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1259,25 +1259,26 @@ 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 @@ -1457,26 +1458,27 @@ 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: 32 additions & 29 deletions plugins/follow_me/follow_me_impl.cpp
Original file line number Diff line number Diff line change
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
16 changes: 8 additions & 8 deletions plugins/offboard/include/plugins/offboard/offboard.h
Original file line number Diff line number Diff line change
Expand Up @@ -273,17 +273,17 @@ std::ostream &operator<<(std::ostream &str,
Offboard::VelocityBodyYawspeed const &velocity_body_yawspeed);

/**
* @brief Equal operator to compare two `Offboard::VelocityNEDYaw` objects.
*
* @return `true` if items are equal.
*/
* @brief Equal operator to compare two `Offboard::VelocityNEDYaw` objects.
*
* @return `true` if items are equal.
*/
bool operator==(const Offboard::VelocityNEDYaw &lhs, const Offboard::VelocityNEDYaw &rhs);

/**
* @brief Stream operator to print information about a `Offboard::VelocityNEDYaw`.
*
* @return A reference to the stream.
*/
* @brief Stream operator to print information about a `Offboard::VelocityNEDYaw`.
*
* @return A reference to the stream.
*/
std::ostream &operator<<(std::ostream &str, Offboard::VelocityNEDYaw const &velocity_ned_yaw);

} // namespace dronecode_sdk
25 changes: 8 additions & 17 deletions plugins/offboard/offboard.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,10 +82,8 @@ const char *Offboard::result_str(Result result)

bool operator==(const Offboard::AttitudeRate &lhs, const Offboard::AttitudeRate &rhs)
{
return lhs.roll_deg_s == rhs.roll_deg_s &&
lhs.pitch_deg_s == rhs.pitch_deg_s &&
lhs.yaw_deg_s == rhs.yaw_deg_s &&
lhs.thrust_value == rhs.thrust_value;
return lhs.roll_deg_s == rhs.roll_deg_s && lhs.pitch_deg_s == rhs.pitch_deg_s &&
lhs.yaw_deg_s == rhs.yaw_deg_s && lhs.thrust_value == rhs.thrust_value;
}

std::ostream &operator<<(std::ostream &str, Offboard::AttitudeRate const &attitude_rate)
Expand All @@ -98,27 +96,22 @@ std::ostream &operator<<(std::ostream &str, Offboard::AttitudeRate const &attitu

bool operator==(const Offboard::PositionNEDYaw &lhs, const Offboard::PositionNEDYaw &rhs)
{
return lhs.north_m == rhs.north_m &&
lhs.east_m == rhs.east_m &&
lhs.down_m == rhs.down_m &&
return lhs.north_m == rhs.north_m && lhs.east_m == rhs.east_m && lhs.down_m == rhs.down_m &&
lhs.yaw_deg == rhs.yaw_deg;
}

std::ostream &operator<<(std::ostream &str, Offboard::PositionNEDYaw const &position_ned_yaw)
{
return str << "[north_m: " << position_ned_yaw.north_m
<< ", east_m: " << position_ned_yaw.east_m
<< ", down_m: " << position_ned_yaw.down_m
<< ", east_m: " << position_ned_yaw.east_m << ", down_m: " << position_ned_yaw.down_m
<< ", yaw_deg: " << position_ned_yaw.yaw_deg << "]";
}

bool operator==(const Offboard::VelocityBodyYawspeed &lhs,
const Offboard::VelocityBodyYawspeed &rhs)
{
return lhs.forward_m_s == rhs.forward_m_s &&
lhs.right_m_s == rhs.right_m_s &&
lhs.down_m_s == rhs.down_m_s &&
lhs.yawspeed_deg_s == rhs.yawspeed_deg_s;
return lhs.forward_m_s == rhs.forward_m_s && lhs.right_m_s == rhs.right_m_s &&
lhs.down_m_s == rhs.down_m_s && lhs.yawspeed_deg_s == rhs.yawspeed_deg_s;
}

std::ostream &operator<<(std::ostream &str,
Expand All @@ -132,10 +125,8 @@ std::ostream &operator<<(std::ostream &str,

bool operator==(const Offboard::VelocityNEDYaw &lhs, const Offboard::VelocityNEDYaw &rhs)
{
return lhs.north_m_s == rhs.north_m_s &&
lhs.east_m_s == rhs.east_m_s &&
lhs.down_m_s == rhs.down_m_s &&
lhs.yaw_deg == rhs.yaw_deg;
return lhs.north_m_s == rhs.north_m_s && lhs.east_m_s == rhs.east_m_s &&
lhs.down_m_s == rhs.down_m_s && lhs.yaw_deg == rhs.yaw_deg;
}

std::ostream &operator<<(std::ostream &str, Offboard::VelocityNEDYaw const &velocity_ned_yaw)
Expand Down

0 comments on commit 06969a8

Please sign in to comment.