Skip to content

Commit

Permalink
Fix some warnings (microsoft#2682)
Browse files Browse the repository at this point in the history
* [Unity/cmake] Ignore unknown warning options, unused functions warning

* [cmake] Disable unknown warning option warnings

* Make base class destructors virtual

* [Car] Remove unused variable state_

* [Mavlinkcom] Remove some unused variables

* [ros] Fix warnings

* Fix misleading indentation warning in RpclibServerBase

* MavlinkNodeImpl: Fix warning to catch exception by const reference
  • Loading branch information
rajat2004 authored Jul 21, 2020
1 parent af1fab6 commit c93eee5
Show file tree
Hide file tree
Showing 16 changed files with 26 additions and 17 deletions.
2 changes: 2 additions & 0 deletions AirLib/include/sensors/SensorFactory.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,8 @@ class SensorFactory {
}
}
}

virtual ~SensorFactory() = default;
};


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ class ArduRoverApi : public CarApiBase {
ArduRoverApi(const AirSimSettings::VehicleSetting* vehicle_setting, std::shared_ptr<SensorFactory> sensor_factory,
const Kinematics::State& state, const Environment& environment, const msr::airlib::GeoPoint& home_geopoint)
: CarApiBase(vehicle_setting, sensor_factory, state, environment),
state_(state), home_geopoint_(home_geopoint)
home_geopoint_(home_geopoint)
{
connection_info_ = static_cast<const AirSimSettings::MavLinkVehicleSetting*>(vehicle_setting)->connection_info;
sensors_ = &getSensors();
Expand Down Expand Up @@ -277,7 +277,6 @@ class ArduRoverApi : public CarApiBase {
const SensorCollection* sensors_;

CarControls last_controls_;
const Kinematics::State& state_;
GeoPoint home_geopoint_;
CarState last_car_state_;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ class PhysXCarApi : public CarApiBase {
PhysXCarApi(const AirSimSettings::VehicleSetting* vehicle_setting, std::shared_ptr<SensorFactory> sensor_factory,
const Kinematics::State& state, const Environment& environment, const msr::airlib::GeoPoint& home_geopoint)
: CarApiBase(vehicle_setting, sensor_factory, state, environment),
home_geopoint_(home_geopoint), state_(state)
home_geopoint_(home_geopoint)
{}

~PhysXCarApi()
Expand Down Expand Up @@ -88,7 +88,6 @@ class PhysXCarApi : public CarApiBase {
bool api_control_enabled_ = false;
GeoPoint home_geopoint_;
CarControls last_controls_;
const Kinematics::State& state_;
CarState last_car_state_;

};
Expand Down
3 changes: 2 additions & 1 deletion AirLib/src/api/RpcLibServerBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -181,7 +181,8 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string&
sim_world_api->reset();
else
getVehicleApi("")->reset();
resetInProgress = false;

resetInProgress = false;
});

pimpl_->server.bind("simPrintLogMessage", [&](const std::string& message, const std::string& message_param, unsigned char severity) -> void {
Expand Down
1 change: 1 addition & 0 deletions AirLibUnitTests/TestBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@ namespace msr { namespace airlib {

class TestBase {
public:
virtual ~TestBase() = default;
virtual void run() = 0;

void testAssert(double lhs, double rhs, const std::string& message) {
Expand Down
2 changes: 0 additions & 2 deletions MavLinkCom/src/impl/MavLinkConnectionImpl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -430,8 +430,6 @@ void MavLinkConnectionImpl::readPackets()
}
else if (frame_state == MAVLINK_FRAMING_OK)
{
int msgId = msg.msgid;

// pick up the sysid/compid of the remote node we are connected to.
if (other_system_id == -1) {
other_system_id = msg.sysid;
Expand Down
3 changes: 2 additions & 1 deletion MavLinkCom/src/impl/MavLinkNodeImpl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -592,8 +592,9 @@ void MavLinkNodeImpl::sendCommand(MavLinkCommand& command)
try {
sendMessage(cmd);
}
catch (std::exception e) {
catch (const std::exception& e) {
// silently fail since we are on a background thread here...
unused(e);
}
}

Expand Down
2 changes: 1 addition & 1 deletion MavLinkCom/src/impl/MavLinkNodeImpl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ namespace mavlinkcom_impl {
{
public:
MavLinkNodeImpl(int localSystemId, int localComponentId);
~MavLinkNodeImpl();
virtual ~MavLinkNodeImpl();

void connect(std::shared_ptr<MavLinkConnection> connection);
void close();
Expand Down
2 changes: 1 addition & 1 deletion MavLinkCom/src/serial_com/SerialPort.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ class SerialPort : public Port
{
public:
SerialPort();
~SerialPort();
virtual ~SerialPort();

// open the serial port
virtual int connect(const char* portName, int baudRate);
Expand Down
2 changes: 0 additions & 2 deletions MavLinkCom/src/serial_com/TcpClientPort.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -227,7 +227,6 @@ class TcpClientPort::TcpSocketImpl
// write to the serial port
int write(const uint8_t* ptr, int count)
{
socklen_t addrlen = sizeof(sockaddr_in);
int hr = send(sock, reinterpret_cast<const char*>(ptr), count, 0);
if (hr == SOCKET_ERROR)
{
Expand Down Expand Up @@ -262,7 +261,6 @@ class TcpClientPort::TcpSocketImpl

while (!closed_)
{
socklen_t addrlen = sizeof(sockaddr_in);
int rc = recv(sock, reinterpret_cast<char*>(result), bytesToRead, 0);
if (rc < 0)
{
Expand Down
2 changes: 1 addition & 1 deletion MavLinkCom/src/serial_com/TcpClientPort.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ class TcpClientPort : public Port
{
public:
TcpClientPort();
~TcpClientPort();
virtual ~TcpClientPort();

// Connect can set you up two different ways. Pass 0 for local port to get any free local
// port. localHost allows you to be specific about which local adapter to use in case you
Expand Down
2 changes: 1 addition & 1 deletion MavLinkCom/src/serial_com/UdpClientPort.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ class UdpClientPort : public Port
{
public:
UdpClientPort();
~UdpClientPort();
virtual ~UdpClientPort();

// Connect can set you up two different ways. Pass 0 for local port to get any free local
// port and pass a fixed remotePort if you want to send to a specific remote port.
Expand Down
4 changes: 2 additions & 2 deletions Unity/AirLibWrapper/AirsimWrapper/cmake/rpc-setup.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -125,7 +125,7 @@ if ("${CMAKE_CXX_COMPILER_ID}" MATCHES "Clang")
# clang is the compiler used for developing mainly, so
# this is where I set the highest warning level
list(APPEND RPCLIB_BUILD_FLAGS
-Wall -Wextra -Wno-c++98-compat
-Wall -Wextra -Wno-unused-function -Wno-c++98-compat -Wno-unknown-warning-option
-Wno-c++98-compat-pedantic -Wno-padded -Wno-missing-prototypes
-Wno-undef -pthread)

Expand Down Expand Up @@ -268,7 +268,7 @@ if ("${CMAKE_CXX_COMPILER_ID}" MATCHES "Clang")
# clang is the compiler used for developing mainly, so
# this is where I set the highest warning level
list(APPEND RPCLIB_BUILD_FLAGS
-Wall -Wextra -Wno-c++98-compat
-Wall -Wextra -Wno-unused-function -Wno-c++98-compat -Wno-unknown-warning-option
-Wno-c++98-compat-pedantic -Wno-padded -Wno-missing-prototypes
-Wno-undef -pthread)

Expand Down
2 changes: 1 addition & 1 deletion cmake/cmake-modules/CommonSetup.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ macro(CommonSetup)
${RPC_LIB_DEFINES} ${CMAKE_CXX_FLAGS}")

if (${CMAKE_CXX_COMPILER_ID} MATCHES "Clang")
set(CMAKE_CXX_FLAGS "-stdlib=libc++ -Wno-documentation ${CMAKE_CXX_FLAGS}")
set(CMAKE_CXX_FLAGS "-stdlib=libc++ -Wno-documentation -Wno-unknown-warning-option ${CMAKE_CXX_FLAGS}")
set(CXX_EXP_LIB "-lc++fs -ferror-limit=10")
else()
set(CXX_EXP_LIB "-lstdc++fs -fmax-errors=10 -Wnoexcept -Wstrict-null-sentinel")
Expand Down
2 changes: 2 additions & 0 deletions ros/src/airsim_ros_pkgs/src/airsim_settings_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,8 @@ bool AirSimSettingsParser::initializeSettings()
std::cout << "simmode_name: " << simmode_name << std::endl;

AirSimSettings::singleton().load(std::bind(&AirSimSettingsParser::getSimMode, this));

return true;
}
else
{
Expand Down
8 changes: 8 additions & 0 deletions ros/src/airsim_ros_pkgs/src/pd_position_controller_simple.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -127,6 +127,10 @@ bool PIDPositionController::local_position_goal_srv_cb(airsim_ros_pkgs::SetLocal
reset_errors(); // todo
return true;
}

// Already have goal, and have reached it
ROS_INFO_STREAM("[PIDPositionController] Already have goal and have reached it");
return false;
}

bool PIDPositionController::local_position_goal_srv_override_cb(airsim_ros_pkgs::SetLocalPosition::Request& request, airsim_ros_pkgs::SetLocalPosition::Response& response)
Expand Down Expand Up @@ -206,6 +210,10 @@ bool PIDPositionController::gps_goal_srv_cb(airsim_ros_pkgs::SetGPSPosition::Req
reset_errors(); // todo
return true;
}

// Already have goal, this shouldn't happen
ROS_INFO_STREAM("[PIDPositionController] Goal already received, ignoring!");
return false;
}

// todo do relative altitude, or add an option for the same?
Expand Down

0 comments on commit c93eee5

Please sign in to comment.