Skip to content

Commit

Permalink
fix remaining compiler warnings.
Browse files Browse the repository at this point in the history
  • Loading branch information
lovettchris committed May 9, 2017
1 parent 08900e8 commit a1d4a62
Show file tree
Hide file tree
Showing 10 changed files with 34 additions and 5 deletions.
5 changes: 4 additions & 1 deletion MavLinkCom/MavLinkTest/Commands.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,8 @@ void Command::Execute(std::shared_ptr<MavLinkVehicle> com)

if (subscription == 0)
{
subscription = com->getConnection()->subscribe([=](std::shared_ptr<MavLinkConnection> con, const MavLinkMessage& msg) {
subscription = com->getConnection()->subscribe([=](std::shared_ptr<MavLinkConnection> connection, const MavLinkMessage& msg) {
unused(connection);
try {
HandleMessage(msg);
}
Expand Down Expand Up @@ -468,6 +469,7 @@ void DumpLogCommandsCommand::processLogCommands(MavLinkFileLog& log, const std::

void DumpLogCommandsCommand::Execute(std::shared_ptr<MavLinkVehicle> com)
{
unused(com);
//TODO: make below future proof (i.e. usable by C++17 compiler) - also change same in main.cpp
#if defined(__cpp_lib_experimental_filesystem)
using namespace std::experimental::filesystem::v1;
Expand Down Expand Up @@ -1368,6 +1370,7 @@ class StreamBuffer {

void SendImageCommand::Execute(std::shared_ptr<MavLinkVehicle> com)
{
unused(com);
if (logViewer.get() == nullptr)
{
printf("sendimage needs a logviewer (use -log on the command line)\n");
Expand Down
1 change: 1 addition & 0 deletions MavLinkCom/MavLinkTest/Commands.h
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,7 @@ class Command
// you must call this method if you want HandleMessage to be called subsequently.
virtual void Execute(std::shared_ptr<MavLinkVehicle> com);
virtual void HandleMessage(const MavLinkMessage& msg) {
unused(msg);
}

static std::vector<std::string> parseArgs(std::string s);
Expand Down
4 changes: 4 additions & 0 deletions MavLinkCom/common_utils/Utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,10 @@ using std::experimental::optional;
*/


// Call this on a function parameter to suppress the unused paramter warning
template <class T> inline
void unused(T const & result) { static_cast<void>(result); }

namespace mavlink_utils {

class Utils {
Expand Down
6 changes: 4 additions & 2 deletions MavLinkCom/src/impl/MavLinkConnectionImpl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -330,14 +330,16 @@ void MavLinkConnectionImpl::unsubscribe(int id)
}
}

void MavLinkConnectionImpl::joinLeftSubscriber(std::shared_ptr<MavLinkConnection> remote, std::shared_ptr<MavLinkConnection> con, const MavLinkMessage& msg)
void MavLinkConnectionImpl::joinLeftSubscriber(std::shared_ptr<MavLinkConnection> remote, std::shared_ptr<MavLinkConnection> connection, const MavLinkMessage& msg)
{
unused(connection);
// forward messages from our connected node to the remote proxy.
remote->sendMessage(msg);
}

void MavLinkConnectionImpl::joinRightSubscriber(std::shared_ptr<MavLinkConnection> con, const MavLinkMessage& msg)
void MavLinkConnectionImpl::joinRightSubscriber(std::shared_ptr<MavLinkConnection> connection, const MavLinkMessage& msg)
{
unused(connection);
// forward messages from remote proxy to local connected node
this->sendMessage(msg);
}
Expand Down
3 changes: 2 additions & 1 deletion MavLinkCom/src/impl/MavLinkFtpClientImpl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,8 @@ bool MavLinkFtpClientImpl::isSupported()
void MavLinkFtpClientImpl::subscribe()
{
if (subscription_ == 0) {
subscription_ = getConnection()->subscribe([=](std::shared_ptr<MavLinkConnection> con, const MavLinkMessage& msg) {
subscription_ = getConnection()->subscribe([=](std::shared_ptr<MavLinkConnection> connection, const MavLinkMessage& msg) {
unused(connection);
handleResponse(msg);
});
}
Expand Down
10 changes: 10 additions & 0 deletions MavLinkCom/src/impl/MavLinkNodeImpl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,8 @@ void MavLinkNodeImpl::sendHeartbeat()
// this is called for all messages received on the connection.
void MavLinkNodeImpl::handleMessage(std::shared_ptr<MavLinkConnection> connection, const MavLinkMessage& msg)
{
unused(connection);
unused(msg);
// this is for the subclasses to play with. We put nothing here so we are not dependent on the
// subclasses remembering to call this base implementation.
}
Expand Down Expand Up @@ -93,6 +95,7 @@ AsyncResult<MavLinkAutopilotVersion> MavLinkNodeImpl::getCapabilities()
{
if (has_cap_) {
AsyncResult<MavLinkAutopilotVersion> nowait([=](int state) {
unused(state);
});
nowait.setResult(cap_);
return nowait;
Expand All @@ -105,6 +108,7 @@ AsyncResult<MavLinkAutopilotVersion> MavLinkNodeImpl::getCapabilities()
});

int subscription = con->subscribe([=](std::shared_ptr<MavLinkConnection> connection, const MavLinkMessage& m) {
unused(connection);
if (m.msgid == static_cast<uint8_t>(MavLinkMessageIds::MAVLINK_MSG_ID_AUTOPILOT_VERSION))
{
cap_.decode(m);
Expand Down Expand Up @@ -136,6 +140,7 @@ AsyncResult<MavLinkHeartbeat> MavLinkNodeImpl::waitForHeartbeat()
});

int subscription = con->subscribe([=](std::shared_ptr<MavLinkConnection> connection, const MavLinkMessage& m) {
unused(connection);
if (m.msgid == static_cast<uint8_t>(MavLinkMessageIds::MAVLINK_MSG_ID_HEARTBEAT))
{
MavLinkHeartbeat heartbeat;
Expand Down Expand Up @@ -272,6 +277,7 @@ std::vector<MavLinkParameter> MavLinkNodeImpl::getParamList()

auto con = ensureConnection();
int subscription = con->subscribe([&](std::shared_ptr<MavLinkConnection> connection, const MavLinkMessage& message) {
unused(connection);
if (message.msgid == MavLinkParamValue::kMessageId)
{
MavLinkParamValue param;
Expand Down Expand Up @@ -397,6 +403,7 @@ AsyncResult<MavLinkParameter> MavLinkNodeImpl::getParameter(const std::string& n
cmd.target_system = getTargetSystemId();

int subscription = con->subscribe([=](std::shared_ptr<MavLinkConnection> connection, const MavLinkMessage& message) {
unused(connection);
if (message.msgid == MavLinkParamValue::kMessageId)
{
MavLinkParamValue param;
Expand Down Expand Up @@ -433,6 +440,7 @@ AsyncResult<MavLinkParameter> MavLinkNodeImpl::getParameterByIndex(int16_t index
cmd.target_system = getTargetSystemId();

int subscription = con->subscribe([=](std::shared_ptr<MavLinkConnection> connection, const MavLinkMessage& message) {
unused(connection);
if (message.msgid == MavLinkParamValue::kMessageId)
{
MavLinkParamValue param;
Expand Down Expand Up @@ -492,6 +500,7 @@ AsyncResult<bool> MavLinkNodeImpl::setParameter(MavLinkParameter p)

// confirmation of the PARAM_SET is to receive the updated PARAM_VALUE.
int subscription = con->subscribe([=](std::shared_ptr<MavLinkConnection> connection, const MavLinkMessage& message) {
unused(connection);
if (message.msgid == MavLinkParamValue::kMessageId)
{
MavLinkParamValue param;
Expand Down Expand Up @@ -556,6 +565,7 @@ AsyncResult<bool> MavLinkNodeImpl::sendCommandAndWaitForAck(MavLinkCommand& comm
uint16_t cmd = command.command;

int subscription = con->subscribe([=](std::shared_ptr<MavLinkConnection> connection, const MavLinkMessage& message) {
unused(connection);
if (message.msgid == MavLinkCommandAck::kMessageId)
{
MavLinkCommandAck ack;
Expand Down
3 changes: 3 additions & 0 deletions MavLinkCom/src/impl/MavLinkVehicleImpl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -127,6 +127,7 @@ AsyncResult<MavLinkHomePosition> MavLinkVehicleImpl::waitForHomePosition()
this->setMessageInterval(static_cast<int>(MavLinkMessageIds::MAVLINK_MSG_ID_HOME_POSITION), 1);

int subscription = con->subscribe([=](std::shared_ptr<MavLinkConnection> connection, const MavLinkMessage& m) {
unused(connection);
if (m.msgid == static_cast<uint8_t>(MavLinkMessageIds::MAVLINK_MSG_ID_HOME_POSITION)) {
MavLinkHomePosition pos;
pos.decode(m);
Expand All @@ -147,6 +148,7 @@ AsyncResult<bool> MavLinkVehicleImpl::allowFlightControlOverUsb()

void MavLinkVehicleImpl::handleMessage(std::shared_ptr<MavLinkConnection> connection, const MavLinkMessage& msg)
{
unused(connection);
//status messages should usually be only sent by actual PX4. However if someone else is sending it to, we should listen it.
//in future it would be good to have ability to add system IDs we are interested in
//if (msg.sysid != getTargetSystemId())
Expand Down Expand Up @@ -483,6 +485,7 @@ AsyncResult<bool> MavLinkVehicleImpl::waitForAltitude(float z, float dz, float d
});

int subscription = con->subscribe([=](std::shared_ptr<MavLinkConnection> connection, const MavLinkMessage& m) {
unused(connection);
if (m.msgid == static_cast<uint8_t>(MavLinkLocalPositionNed::kMessageId)) {
MavLinkLocalPositionNed pos;
pos.decode(m);
Expand Down
2 changes: 2 additions & 0 deletions MavLinkCom/src/impl/MavLinkVideoStreamImpl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@ MavLinkVideoClientImpl::~MavLinkVideoClientImpl()

void MavLinkVideoClientImpl::handleMessage(std::shared_ptr<MavLinkConnection> connection, const MavLinkMessage& message)
{
unused(connection);
switch (message.msgid)
{
case MavLinkDataTransmissionHandshake::kMessageId: //MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
Expand Down Expand Up @@ -121,6 +122,7 @@ MavLinkVideoServerImpl::~MavLinkVideoServerImpl()

void MavLinkVideoServerImpl::handleMessage(std::shared_ptr<MavLinkConnection> connection, const MavLinkMessage& message)
{
unused(connection);
switch (message.msgid)
{
case MavLinkCommandLong::kMessageId:
Expand Down
3 changes: 2 additions & 1 deletion MavLinkCom/src/serial_com/SerialPort.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
#include <Wbemidl.h>
#include <string>
#include "Windows.h"

#include "Utils.hpp"
#pragma comment(lib, "wbemuuid.lib")

class SerialPort::serialport_impl
Expand Down Expand Up @@ -330,6 +330,7 @@ class SerialPort::serialport_impl

int setAttributes(int baudRate, Parity parity, int dataBits, StopBits stopBits, Handshake handshake, int readTimeout, int writeTimeout)
{
unused(writeTimeout);
struct termios tty;
::memset(&tty, 0, sizeof tty);
if (tcgetattr(fd, &tty) != 0)
Expand Down
2 changes: 2 additions & 0 deletions MavLinkCom/src/serial_com/SerialPort.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
#include <string>
#include <memory>
#include "Port.h"
#include "Utils.hpp"

enum Parity {
Parity_None = (0x0100),
Expand Down Expand Up @@ -53,6 +54,7 @@ class SerialPort : public Port
virtual bool isClosed();

virtual int getRssi(const char* ifaceName) {
unused(ifaceName);
return 0; // not supported on serial port.
}
private:
Expand Down

0 comments on commit a1d4a62

Please sign in to comment.