Skip to content

Commit

Permalink
Merge 659c050 into 27027d4
Browse files Browse the repository at this point in the history
  • Loading branch information
julianoes committed Jul 6, 2018
2 parents 27027d4 + 659c050 commit 54b688b
Show file tree
Hide file tree
Showing 20 changed files with 86 additions and 36 deletions.
5 changes: 3 additions & 2 deletions core/global_include.cpp
Expand Up @@ -3,6 +3,7 @@
#include <cfloat>
#include <cstdint>
#include <limits>
#include <cmath>

namespace dronecode_sdk {

Expand Down Expand Up @@ -149,12 +150,12 @@ float to_deg_from_rad(float rad)

bool are_equal(float one, float two)
{
return (fabsf(one - two) < std::numeric_limits<float>::epsilon());
return (std::fabs(one - two) < std::numeric_limits<float>::epsilon());
}

bool are_equal(double one, double two)
{
return (fabs(one - two) < std::numeric_limits<double>::epsilon());
return (std::fabs(one - two) < std::numeric_limits<double>::epsilon());
}

} // namespace dronecode_sdk
19 changes: 8 additions & 11 deletions core/global_include.h
Expand Up @@ -5,14 +5,15 @@
#include <chrono>
#include <thread>

#ifdef WINDOWS
#ifndef _USE_MATH_DEFINES
#define _USE_MATH_DEFINES
// Instead of using the constant from math.h or cmath we define it ourselves. This way
// we don't import all the other C math functions and make sure to use the C++ functions
// from the standard library (e.g. std::abs() instead of abs()).
#ifndef M_PI
constexpr double M_PI = 3.14159265358979323846;
#endif
// cmath doesn't contain M_PI
#include <math.h>
#else
#include <cmath>

#ifndef M_PI_F
constexpr float M_PI_F = float(M_PI);
#endif

#define MIN(x_, y_) ((x_) > (y_)) ? (y_) : (x_)
Expand All @@ -24,10 +25,6 @@
#define STRNCPY strncpy
#endif

#ifndef M_PI_F
#define M_PI_F float(M_PI)
#endif

namespace dronecode_sdk {

typedef std::chrono::time_point<std::chrono::steady_clock> dl_time_t;
Expand Down
1 change: 1 addition & 0 deletions integration_tests/mission.cpp
Expand Up @@ -3,6 +3,7 @@
#include <memory>
#include <future>
#include <atomic>
#include <cmath>
#include "integration_test_helper.h"
#include "dronecode_sdk.h"
#include "plugins/telemetry/telemetry.h"
Expand Down
1 change: 1 addition & 0 deletions integration_tests/simple_hover.cpp
@@ -1,4 +1,5 @@
#include <iostream>
#include <cmath>
#include "integration_test_helper.h"
#include "dronecode_sdk.h"
#include "plugins/action/action.h"
Expand Down
4 changes: 4 additions & 0 deletions plugins/action/CMakeLists.txt
Expand Up @@ -7,6 +7,10 @@ target_link_libraries(dronecode_sdk_action
dronecode_sdk
)

set_target_properties(dronecode_sdk_action
PROPERTIES COMPILE_FLAGS ${warnings}
)

install(FILES
action.h
action_result.h
Expand Down
4 changes: 4 additions & 0 deletions plugins/calibration/CMakeLists.txt
Expand Up @@ -8,6 +8,10 @@ target_link_libraries(dronecode_sdk_calibration
dronecode_sdk
)

set_target_properties(dronecode_sdk_calibration
PROPERTIES COMPILE_FLAGS ${warnings}
)

install(FILES
calibration.h
DESTINATION ${dronecode_sdk_install_include_dir}
Expand Down
2 changes: 1 addition & 1 deletion plugins/calibration/calibration_impl.cpp
Expand Up @@ -330,7 +330,7 @@ void CalibrationImpl::process_statustext(const mavlink_message_t &message)
// FALLTHROUGH
case CalibrationStatustextParser::Status::CANCELLED:
_calibration_callback = nullptr;
_state == State::NONE;
_state = State::NONE;
break;
default:
break;
Expand Down
4 changes: 4 additions & 0 deletions plugins/camera/CMakeLists.txt
Expand Up @@ -10,6 +10,10 @@ target_link_libraries(dronecode_sdk_camera
${CURL_LIBRARY}
)

set_target_properties(dronecode_sdk_camera
PROPERTIES COMPILE_FLAGS ${warnings}
)

include_directories(
${CURL_INCLUDE_DIRS}
)
Expand Down
19 changes: 13 additions & 6 deletions plugins/camera/camera_impl.cpp
Expand Up @@ -5,6 +5,7 @@
#include "mavlink_include.h"
#include "http_loader.h"
#include <functional>
#include <cmath>

namespace dronecode_sdk {

Expand Down Expand Up @@ -396,8 +397,8 @@ Camera::Result CameraImpl::get_video_stream_info(Camera::VideoStreamInfo &info)
auto prom = std::make_shared<std::promise<Camera::Result>>();
auto ret = prom->get_future();

get_video_stream_info_async([prom](Camera::Result result, Camera::VideoStreamInfo info) {
UNUSED(info);
get_video_stream_info_async([prom](Camera::Result result, Camera::VideoStreamInfo info_gotten) {
UNUSED(info_gotten);
prom->set_value(result);
});

Expand Down Expand Up @@ -426,6 +427,7 @@ void CameraImpl::get_video_stream_info_async(

auto command = make_command_request_video_stream_info();
_parent->send_command_async(command, [this](MAVLinkCommands::Result result, float progress) {
UNUSED(progress);
Camera::Result camera_result = camera_result_from_command_result(result);
if (camera_result != Camera::Result::SUCCESS) {
if (_video_stream_info.callback) {
Expand Down Expand Up @@ -508,8 +510,13 @@ Camera::Result CameraImpl::set_mode(const Camera::Mode mode)

void CameraImpl::save_camera_mode(const float mavlink_camera_mode)
{
if (!std::isfinite(mavlink_camera_mode)) {
LogWarn() << "Can't save NAN as camera mode";
return;
}

MAVLinkParameters::ParamValue value;
value.set_uint32(mavlink_camera_mode);
value.set_uint32(uint32_t(mavlink_camera_mode));
_camera_definition->set_setting("CAM_MODE", value);
refresh_params();
}
Expand Down Expand Up @@ -1102,7 +1109,7 @@ void CameraImpl::get_option_async(const std::string &setting_id,
LogWarn() << "The param was probably outdated, trying to fetch it";
_parent->get_param_async(
setting_id,
[setting_id, this](bool success, MAVLinkParameters::ParamValue value) {
[setting_id, this](bool success, MAVLinkParameters::ParamValue value_gotten) {
if (!success) {
LogWarn() << "Fetching the param failed";
return;
Expand All @@ -1111,7 +1118,7 @@ void CameraImpl::get_option_async(const std::string &setting_id,
if (!this->_camera_definition) {
return;
}
this->_camera_definition->set_setting(setting_id, value);
this->_camera_definition->set_setting(setting_id, value_gotten);
},
true);

Expand Down Expand Up @@ -1204,7 +1211,7 @@ void CameraImpl::refresh_params()
return;
}

int count = 0;
unsigned count = 0;
for (const auto &param : params) {
std::string param_name = param;
const bool is_last = (count + 1 == params.size());
Expand Down
4 changes: 4 additions & 0 deletions plugins/follow_me/CMakeLists.txt
Expand Up @@ -7,6 +7,10 @@ target_link_libraries(dronecode_sdk_follow_me
dronecode_sdk
)

set_target_properties(dronecode_sdk_follow_me
PROPERTIES COMPILE_FLAGS ${warnings}
)

install(FILES
follow_me.h
DESTINATION ${dronecode_sdk_install_include_dir}
Expand Down
4 changes: 4 additions & 0 deletions plugins/gimbal/CMakeLists.txt
Expand Up @@ -7,6 +7,10 @@ target_link_libraries(dronecode_sdk_gimbal
dronecode_sdk
)

set_target_properties(dronecode_sdk_gimbal
PROPERTIES COMPILE_FLAGS ${warnings}
)

install(FILES
gimbal.h
DESTINATION ${dronecode_sdk_install_include_dir}
Expand Down
4 changes: 4 additions & 0 deletions plugins/info/CMakeLists.txt
Expand Up @@ -7,6 +7,10 @@ target_link_libraries(dronecode_sdk_info
dronecode_sdk
)

set_target_properties(dronecode_sdk_info
PROPERTIES COMPILE_FLAGS ${warnings}
)

install(FILES
info.h
DESTINATION ${dronecode_sdk_install_include_dir}
Expand Down
4 changes: 2 additions & 2 deletions plugins/info/info_impl.cpp
Expand Up @@ -100,11 +100,11 @@ void InfoImpl::process_autopilot_version(const mavlink_message_t &message)

product.vendor_id = autopilot_version.vendor_id;
const char *vendor_name = vendor_id_str(autopilot_version.vendor_id);
STRNCPY(product.vendor_name, vendor_name, sizeof(product.vendor_name));
STRNCPY(product.vendor_name, vendor_name, sizeof(product.vendor_name) - 1);

product.product_id = autopilot_version.product_id;
const char *product_name = product_id_str(autopilot_version.product_id);
STRNCPY(product.product_name, product_name, sizeof(product.product_name));
STRNCPY(product.product_name, product_name, sizeof(product.product_name) - 1);

set_product(product);
}
Expand Down
4 changes: 4 additions & 0 deletions plugins/logging/CMakeLists.txt
Expand Up @@ -7,6 +7,10 @@ target_link_libraries(dronecode_sdk_logging
dronecode_sdk
)

set_target_properties(dronecode_sdk_logging
PROPERTIES COMPILE_FLAGS ${warnings}
)

install(FILES
logging.h
DESTINATION ${dronecode_sdk_install_include_dir}
Expand Down
4 changes: 4 additions & 0 deletions plugins/mission/CMakeLists.txt
Expand Up @@ -10,6 +10,10 @@ include_directories(
SYSTEM third_party/json11
)

set_target_properties(dronecode_sdk_mission
PROPERTIES COMPILE_FLAGS ${warnings}
)

# JSON parser library for parsing QGC plan for Mission
add_subdirectory(third_party/json11)

Expand Down
2 changes: 1 addition & 1 deletion plugins/mission/mission_impl.cpp
Expand Up @@ -1210,7 +1210,7 @@ Mission::Result MissionImpl::import_mission_items(Mission::mission_items_t &all_
for (auto &p : json_mission_item["params"].array_items()) {
if (p.is_null()) {
// QGC sets params as `null` if they should be unchanged.
params.push_back(NAN);
params.push_back(double(NAN));
} else {
params.push_back(p.number_value());
}
Expand Down
2 changes: 1 addition & 1 deletion plugins/mission/mission_import_qgc_test.cpp
Expand Up @@ -5,7 +5,7 @@

#include <gtest/gtest.h>
#include <atomic>
#include <atomic>
#include <cmath>
#include "mission.h"
#include "mavlink_include.h"
#include "global_include.h"
Expand Down
4 changes: 4 additions & 0 deletions plugins/offboard/CMakeLists.txt
Expand Up @@ -7,6 +7,10 @@ target_link_libraries(dronecode_sdk_offboard
dronecode_sdk
)

set_target_properties(dronecode_sdk_offboard
PROPERTIES COMPILE_FLAGS ${warnings}
)

install(FILES
offboard.h
DESTINATION ${dronecode_sdk_install_include_dir}
Expand Down
4 changes: 4 additions & 0 deletions plugins/telemetry/CMakeLists.txt
Expand Up @@ -8,6 +8,10 @@ target_link_libraries(dronecode_sdk_telemetry
dronecode_sdk
)

set_target_properties(dronecode_sdk_telemetry
PROPERTIES COMPILE_FLAGS ${warnings}
)

install(FILES
telemetry.h
DESTINATION ${dronecode_sdk_install_include_dir}
Expand Down
27 changes: 15 additions & 12 deletions plugins/telemetry/telemetry.cpp
@@ -1,6 +1,7 @@
#include "telemetry.h"

#include <limits>
#include <cmath>

#include "telemetry_impl.h"

Expand Down Expand Up @@ -319,27 +320,29 @@ const char *Telemetry::result_str(Result result)
bool operator==(const Telemetry::PositionVelocityNED &lhs,
const Telemetry::PositionVelocityNED &rhs)
{
return abs(lhs.position.north_m - rhs.position.north_m) <=
std::numeric_limits<double>::epsilon() &&
abs(lhs.position.east_m - rhs.position.east_m) <=
std::numeric_limits<double>::epsilon() &&
abs(lhs.position.down_m - rhs.position.down_m) <=
return std::fabs(lhs.position.north_m - rhs.position.north_m) <=
std::numeric_limits<float>::epsilon() &&
std::fabs(lhs.position.east_m - rhs.position.east_m) <=
std::numeric_limits<float>::epsilon() &&
abs(lhs.velocity.north_m_s - rhs.velocity.north_m_s) <=
std::fabs(lhs.position.down_m - rhs.position.down_m) <=
std::numeric_limits<float>::epsilon() &&
abs(lhs.velocity.east_m_s - rhs.velocity.east_m_s) <=
std::fabs(lhs.velocity.north_m_s - rhs.velocity.north_m_s) <=
std::numeric_limits<float>::epsilon() &&
abs(lhs.velocity.down_m_s - rhs.velocity.down_m_s) <=
std::fabs(lhs.velocity.east_m_s - rhs.velocity.east_m_s) <=
std::numeric_limits<float>::epsilon() &&
std::fabs(lhs.velocity.down_m_s - rhs.velocity.down_m_s) <=
std::numeric_limits<float>::epsilon();
}

bool operator==(const Telemetry::Position &lhs, const Telemetry::Position &rhs)
{
return abs(lhs.latitude_deg - rhs.latitude_deg) <= std::numeric_limits<double>::epsilon() &&
abs(lhs.longitude_deg - rhs.longitude_deg) <= std::numeric_limits<double>::epsilon() &&
abs(lhs.absolute_altitude_m - rhs.absolute_altitude_m) <=
return std::abs(lhs.latitude_deg - rhs.latitude_deg) <=
std::numeric_limits<double>::epsilon() &&
std::abs(lhs.longitude_deg - rhs.longitude_deg) <=
std::numeric_limits<double>::epsilon() &&
std::abs(lhs.absolute_altitude_m - rhs.absolute_altitude_m) <=
std::numeric_limits<float>::epsilon() &&
abs(lhs.relative_altitude_m - rhs.relative_altitude_m) <=
std::abs(lhs.relative_altitude_m - rhs.relative_altitude_m) <=
std::numeric_limits<float>::epsilon();
}

Expand Down

0 comments on commit 54b688b

Please sign in to comment.