Skip to content

Commit

Permalink
Clean build on Linux using GCC 6
Browse files Browse the repository at this point in the history
  • Loading branch information
clovett committed Feb 18, 2017
1 parent 847744c commit 8b951e1
Show file tree
Hide file tree
Showing 25 changed files with 87 additions and 2,060 deletions.
8 changes: 4 additions & 4 deletions AirLib/include/common/EarthUtils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,8 +54,8 @@ class EarthUtils {
}

/* round down to nearest sampling resolution */
int min_lat = (int)(latitude / MAG_SAMPLING_RES) * MAG_SAMPLING_RES;
int min_lon = (int)(longitude / MAG_SAMPLING_RES) * MAG_SAMPLING_RES;
int min_lat = static_cast<int>(latitude / MAG_SAMPLING_RES) * MAG_SAMPLING_RES;
int min_lon = static_cast<int>(longitude / MAG_SAMPLING_RES) * MAG_SAMPLING_RES;

/* for the rare case of hitting the bounds exactly
* the rounding logic wouldn't fit, so enforce it.
Expand All @@ -67,15 +67,15 @@ class EarthUtils {
}

if (latitude >= MAG_SAMPLING_MAX_LAT) {
min_lat = (int)(latitude / MAG_SAMPLING_RES) * MAG_SAMPLING_RES - MAG_SAMPLING_RES;
min_lat = static_cast<int>(latitude / MAG_SAMPLING_RES) * MAG_SAMPLING_RES - MAG_SAMPLING_RES;
}

if (longitude <= MAG_SAMPLING_MIN_LON) {
min_lon = MAG_SAMPLING_MIN_LON;
}

if (longitude >= MAG_SAMPLING_MAX_LON) {
min_lon = (int)(longitude / MAG_SAMPLING_RES) * MAG_SAMPLING_RES - MAG_SAMPLING_RES;
min_lon = static_cast<int>(longitude / MAG_SAMPLING_RES) * MAG_SAMPLING_RES - MAG_SAMPLING_RES;
}

/* find index of nearest low sampling point */
Expand Down
13 changes: 7 additions & 6 deletions AirLib/include/common/common_utils/StrictMode.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,15 +18,16 @@
#ifdef __GNUC__
#define STRICT_MODE_OFF \
_Pragma("GCC diagnostic push") \
_Pragma("GCC diagnostic ignored \"-Wreturn-type\"") \
_Pragma("GCC diagnostic ignored \"-Wctor-dtor-privacy\"") \
_Pragma("GCC diagnostic ignored \"-Wdelete-non-virtual-dtor\"") \
_Pragma("GCC diagnostic ignored \"-Wunused-parameter\"") \
_Pragma("GCC diagnostic ignored \"-pedantic\"") \
_Pragma("GCC diagnostic ignored \"-Wshadow\"") \
_Pragma("GCC diagnostic ignored \"-Wmissing-field-initializers\"") \
_Pragma("GCC diagnostic ignored \"-Wold-style-cast\"") \
_Pragma("GCC diagnostic ignored \"-Wredundant-decls\"") \
_Pragma("GCC diagnostic ignored \"-Wreturn-type\"") \
_Pragma("GCC diagnostic ignored \"-Wshadow\"") \
_Pragma("GCC diagnostic ignored \"-Wswitch-default\"") \
_Pragma("GCC diagnostic ignored \"-Wmissing-field-initializers\"") \
_Pragma("GCC diagnostic ignored \"-Wredundant-decls\"")
_Pragma("GCC diagnostic ignored \"-Wundef\"") \
_Pragma("GCC diagnostic ignored \"-Wunused-parameter\"")

/* Addition options that can be enabled
_Pragma("GCC diagnostic ignored \"-Wpedantic\"") \
Expand Down
9 changes: 6 additions & 3 deletions AirLib/include/common/common_utils/Utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,9 @@

#include "type_utils.hpp"

#ifndef _WIN32
#include <limits.h> // needed for CHAR_BIT used below
#endif

//Stubs for C++17 optional type
#if (defined __cplusplus) && (__cplusplus >= 201700L)
Expand All @@ -42,15 +45,15 @@ using std::experimental::optional;
#include <cmath>

#ifndef M_PIf
#define M_PIf ((float)3.1415926535897932384626433832795028841972)
#define M_PIf static_cast<float>(3.1415926535897932384626433832795028841972)
#endif

#ifndef M_PI
#define M_PI ((double)3.1415926535897932384626433832795028841972)
#define M_PI static_cast<double>(3.1415926535897932384626433832795028841972)
#endif

#ifndef M_PIl
#define M_PIl ((long double)3.1415926535897932384626433832795028841972)
#define M_PIl static_cast<long double>(3.1415926535897932384626433832795028841972)
#endif

#define EARTH_RADIUS (6378137.0f)
Expand Down
5 changes: 5 additions & 0 deletions AirLib/include/control/Settings.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,11 @@
#pragma once
#include <string>

#include "common/common_utils/Utils.hpp"
STRICT_MODE_OFF
// this json library is not strict clean
#include "common/common_utils/json.hpp"
STRICT_MODE_ON

namespace msr {
namespace airlib {
Expand Down
2 changes: 1 addition & 1 deletion AirLib/src/control/RpcLibClient.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -129,7 +129,7 @@ bool RpcLibClient::hover()
bool RpcLibClient::setSafety(SafetyEval::SafetyViolationType enable_reasons, float obs_clearance, SafetyEval::ObsAvoidanceStrategy obs_startegy,
float obs_avoidance_vel, const Vector3r& origin, float xy_length, float max_z, float min_z)
{
return pimpl_->client.call("setSafety", (uint) enable_reasons, obs_clearance, obs_startegy,
return pimpl_->client.call("setSafety", static_cast<uint>(enable_reasons), obs_clearance, obs_startegy,
obs_avoidance_vel, RpcLibAdapators::Vector3r(origin), xy_length, max_z, min_z).as<bool>();
}

Expand Down
6 changes: 2 additions & 4 deletions DroneShell/src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ namespace msr { namespace airlib {

struct CommandContext {
public:
RpcLibClient& client;
RpcLibClient client;
AsyncTasker tasker;
};

Expand Down Expand Up @@ -991,9 +991,7 @@ int main(int argc, const char *argv[]) {
return -1;
}

RpcLibClient client(server_address);

CommandContext command_context{ client };
CommandContext command_context{ /*RpcClient*/{server_address}, /*AsyncTasker*/ {} };

command_context.tasker.setErrorHandler([](std::exception& e) {
try {
Expand Down
4 changes: 3 additions & 1 deletion MavLinkCom/MavLinkCom.vcxproj.filters
Original file line number Diff line number Diff line change
Expand Up @@ -192,7 +192,9 @@
<ClInclude Include="src\serial_com\UdpServer.hpp">
<Filter>serial_com</Filter>
</ClInclude>
<ClInclude Include="common_utils\StrictMode.hpp" />
<ClInclude Include="common_utils\StrictMode.hpp">
<Filter>common_utils</Filter>
</ClInclude>
</ItemGroup>
<ItemGroup>
<Filter Include="Mavlink">
Expand Down
27 changes: 14 additions & 13 deletions MavLinkCom/common_utils/StrictMode.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,22 +18,23 @@
#ifdef __GNUC__
#define STRICT_MODE_OFF \
_Pragma("GCC diagnostic push") \
_Pragma("GCC diagnostic ignored \"-Wreturn-type\"") \
_Pragma("GCC diagnostic ignored \"-Wctor-dtor-privacy\"") \
_Pragma("GCC diagnostic ignored \"-Wdelete-non-virtual-dtor\"") \
_Pragma("GCC diagnostic ignored \"-Wunused-parameter\"") \
_Pragma("GCC diagnostic ignored \"-pedantic\"") \
_Pragma("GCC diagnostic ignored \"-Wshadow\"") \
_Pragma("GCC diagnostic ignored \"-Wold-style-cast\"") \
_Pragma("GCC diagnostic ignored \"-Wswitch-default\"") \
_Pragma("GCC diagnostic ignored \"-Wmissing-field-initializers\"") \
_Pragma("GCC diagnostic ignored \"-Wredundant-decls\"")
_Pragma("GCC diagnostic ignored \"-Wmissing-field-initializers\"") \
_Pragma("GCC diagnostic ignored \"-Wold-style-cast\"") \
_Pragma("GCC diagnostic ignored \"-Wredundant-decls\"") \
_Pragma("GCC diagnostic ignored \"-Wreturn-type\"") \
_Pragma("GCC diagnostic ignored \"-Wshadow\"") \
_Pragma("GCC diagnostic ignored \"-Wswitch-default\"") \
_Pragma("GCC diagnostic ignored \"-Wundef\"") \
_Pragma("GCC diagnostic ignored \"-Wunused-parameter\"")

/* Addition options that can be enabled
_Pragma("GCC diagnostic ignored \"-Wpedantic\"") \
_Pragma("GCC diagnostic ignored \"-Wformat=\"") \
_Pragma("GCC diagnostic ignored \"-Werror\"") \
_Pragma("GCC diagnostic ignored \"-Werror=\"") \
_Pragma("GCC diagnostic ignored \"-Wunused-variable\"") \
_Pragma("GCC diagnostic ignored \"-Wpedantic\"") \
_Pragma("GCC diagnostic ignored \"-Wformat=\"") \
_Pragma("GCC diagnostic ignored \"-Werror\"") \
_Pragma("GCC diagnostic ignored \"-Werror=\"") \
_Pragma("GCC diagnostic ignored \"-Wunused-variable\"") \
*/

#define STRICT_MODE_ON \
Expand Down
9 changes: 6 additions & 3 deletions MavLinkCom/common_utils/Utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,9 @@
#include "type_utils.hpp"
#include <limits>

#ifndef _WIN32
#include <limits.h> // needed for CHAR_BIT used below
#endif

//Stubs for C++17 optional type
#if (defined __cplusplus) && (__cplusplus >= 201700L)
Expand All @@ -38,15 +41,15 @@ using std::experimental::optional;
#include <cmath>

#ifndef M_PIf
#define M_PIf ((float)3.1415926535897932384626433832795028841972)
#define M_PIf static_cast<float>(3.1415926535897932384626433832795028841972)
#endif

#ifndef M_PI
#define M_PI ((double)3.1415926535897932384626433832795028841972)
#define M_PI static_cast<double>(3.1415926535897932384626433832795028841972)
#endif

#ifndef M_PIl
#define M_PIl ((long double)3.1415926535897932384626433832795028841972)
#define M_PIl static_cast<long double>(3.1415926535897932384626433832795028841972)
#endif

#define EARTH_RADIUS (6378137.0f)
Expand Down
26 changes: 26 additions & 0 deletions MavLinkCom/src/MavLinkMessageBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,55 +34,81 @@ void MavLinkMessageBase::pack_int8_t(char* buffer, const int8_t* field, int offs
}
void MavLinkMessageBase::pack_int16_t(char* buffer, const int16_t* field, int offset) const
{
STRICT_MODE_OFF
_mav_put_int16_t(buffer, offset, *field);
STRICT_MODE_ON
}
void MavLinkMessageBase::pack_uint16_t(char* buffer, const uint16_t* field, int offset) const
{
STRICT_MODE_OFF
_mav_put_uint16_t(buffer, offset, *field);
STRICT_MODE_ON
}
void MavLinkMessageBase::pack_uint32_t(char* buffer, const uint32_t* field, int offset) const
{
STRICT_MODE_OFF
_mav_put_uint32_t(buffer, offset, *field);
STRICT_MODE_ON
}
void MavLinkMessageBase::pack_int32_t(char* buffer, const int32_t* field, int offset) const
{
STRICT_MODE_OFF
_mav_put_int32_t(buffer, offset, *field);
STRICT_MODE_ON
}
void MavLinkMessageBase::pack_uint64_t(char* buffer, const uint64_t* field, int offset) const
{
STRICT_MODE_OFF
_mav_put_uint64_t(buffer, offset, *field);
STRICT_MODE_ON
}
void MavLinkMessageBase::pack_int64_t(char* buffer, const int64_t* field, int offset) const
{
STRICT_MODE_OFF
_mav_put_int64_t(buffer, offset, *field);
STRICT_MODE_ON
}
void MavLinkMessageBase::pack_float(char* buffer, const float* field, int offset) const
{
STRICT_MODE_OFF
_mav_put_float(buffer, offset, *field);
STRICT_MODE_ON
}
void MavLinkMessageBase::pack_char_array(int len, char* buffer, const char* field, int offset) const
{
STRICT_MODE_OFF
_mav_put_char_array(buffer, offset, field, len);
STRICT_MODE_ON
}
void MavLinkMessageBase::pack_uint8_t_array(int len, char* buffer, const uint8_t* field, int offset) const
{
STRICT_MODE_OFF
_mav_put_uint8_t_array(buffer, offset, field, len);
STRICT_MODE_ON
}
void MavLinkMessageBase::pack_int8_t_array(int len, char* buffer, const int8_t* field, int offset) const
{
STRICT_MODE_OFF
_mav_put_int8_t_array(buffer, offset, field, len);
STRICT_MODE_ON
}
void MavLinkMessageBase::pack_uint16_t_array(int len, char* buffer, const uint16_t* field, int offset) const
{
STRICT_MODE_OFF
_mav_put_uint16_t_array(buffer, offset, field, len);
STRICT_MODE_ON
}
void MavLinkMessageBase::pack_int16_t_array(int len, char* buffer, const int16_t* field, int offset) const
{
STRICT_MODE_OFF
_mav_put_int16_t_array(buffer, offset, field, len);
STRICT_MODE_ON
}
void MavLinkMessageBase::pack_float_array(int len, char* buffer, const float* field, int offset) const
{
STRICT_MODE_OFF
_mav_put_float_array(buffer, offset, field, len);
STRICT_MODE_ON
}


Expand Down
4 changes: 4 additions & 0 deletions MavLinkCom/src/impl/MavLinkConnectionImpl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -187,8 +187,12 @@ void MavLinkConnectionImpl::sendMessage(const MavLinkMessageBase& msg)
#if MAVLINK_CRC_EXTRA
crc_accumulate(crc_extra, &m.checksum);
#endif

// these macros use old style cast.
STRICT_MODE_OFF
mavlink_ck_a(&m) = (uint8_t)(m.checksum & 0xFF);
mavlink_ck_b(&m) = (uint8_t)(m.checksum >> 8);
STRICT_MODE_ON

// send the message, now that it is ready
sendMessage(reinterpret_cast<const MavLinkMessage&>(m));
Expand Down
2 changes: 1 addition & 1 deletion MavLinkCom/src/impl/MavLinkFtpClientImpl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -207,7 +207,7 @@ void MavLinkFtpClientImpl::runStateMachine()
std::lock_guard<std::mutex> guard(mutex_);
after = messages_;
if (messages_ > 0) {
rate = (double)total_time_.count() / (double)messages_;
rate = static_cast<double>(total_time_.count()) / static_cast<double>(messages_);
if (progress_ != nullptr)
{
progress_->average_rate = rate;
Expand Down
4 changes: 4 additions & 0 deletions MavLinkCom/src/impl/MavLinkVideoStreamImpl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,6 +86,8 @@ void MavLinkVideoClientImpl::handleMessage(std::shared_ptr<MavLinkConnection> co
}
break;
}
default:
break;
}
}

Expand Down Expand Up @@ -141,6 +143,8 @@ void MavLinkVideoServerImpl::handleMessage(std::shared_ptr<MavLinkConnection> co
break;
}
}
default:
break;
}
}

Expand Down
Loading

0 comments on commit 8b951e1

Please sign in to comment.