Skip to content

Commit

Permalink
made shared_ptr implicit casts explicit
Browse files Browse the repository at this point in the history
  • Loading branch information
admercs committed Mar 3, 2024
1 parent a6c9c65 commit 6a647e1
Show file tree
Hide file tree
Showing 11 changed files with 27 additions and 14 deletions.
1 change: 0 additions & 1 deletion MavLinkCom/MavLinkMoCap/stdafx.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@
#pragma once

#include "targetver.h"

#include <stdio.h>
#include <tchar.h>

Expand Down
3 changes: 1 addition & 2 deletions MavLinkCom/MavLinkTest/Commands.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,15 +5,14 @@
#include "FileSystem.hpp"
#include "Utils.hpp"
#include <chrono>
#include <filesystem>
#include <iostream>
#include <math.h>
#include <string.h>
#include <string>
#include <thread>

#include <filesystem>
using namespace std::filesystem;

using namespace mavlink_utils;
using namespace mavlinkcom;

Expand Down
2 changes: 2 additions & 0 deletions MavLinkCom/MavLinkTest/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@ STRICT_MODE_ON
#include "UnitTests.h"

#include <filesystem>

using namespace std::filesystem;

/* enable math defines on Windows */
Expand All @@ -46,6 +47,7 @@ static const int pixhawkFMUV2OldBootloaderProductId = 22; ///< Product ID for Bo
typedef mavlink_utils::Utils Utils;
typedef mavlink_utils::FileSystem FileSystem;
typedef unsigned int uint;

using namespace mavlinkcom;

struct FlagName {
Expand Down
1 change: 1 addition & 0 deletions MavLinkCom/src/MavLinkMessages.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@
// Licensed under the MIT License.
#include "MavLinkMessages.hpp"
#include <sstream>

using namespace mavlinkcom;

int MavLinkHeartbeat::pack(char *buffer) const {
Expand Down
13 changes: 8 additions & 5 deletions MavLinkCom/src/impl/AdHocConnectionImpl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,8 @@ std::shared_ptr<AdHocConnection> AdHocConnectionImpl::connectLocalUdp(const std:
std::string localAddr, int localPort) {
std::shared_ptr<UdpClientPort> socket = std::make_shared<UdpClientPort>();
socket->connect(localAddr, localPort, "", 0);
return createConnection(nodeName, socket);
std::shared_ptr<Port> port = socket;
return createConnection(nodeName, port);
}

std::shared_ptr<AdHocConnection> AdHocConnectionImpl::connectRemoteUdp(const std::string &nodeName,
Expand All @@ -51,7 +52,8 @@ std::shared_ptr<AdHocConnection> AdHocConnectionImpl::connectRemoteUdp(const std

std::shared_ptr<UdpClientPort> socket = std::make_shared<UdpClientPort>();
socket->connect(local, 0, remoteAddr, remotePort);
return createConnection(nodeName, socket);
std::shared_ptr<Port> port = socket;
return createConnection(nodeName, port);
}

std::shared_ptr<AdHocConnection> AdHocConnectionImpl::connectTcp(const std::string &nodeName, std::string localAddr,
Expand All @@ -64,7 +66,8 @@ std::shared_ptr<AdHocConnection> AdHocConnectionImpl::connectTcp(const std::stri

std::shared_ptr<TcpClientPort> socket = std::make_shared<TcpClientPort>();
socket->connect(local, 0, remoteIpAddr, remotePort);
return createConnection(nodeName, socket);
std::shared_ptr<Port> port = socket;
return createConnection(nodeName, port);
}

std::shared_ptr<AdHocConnection> AdHocConnectionImpl::connectSerial(const std::string &nodeName, std::string name,
Expand All @@ -79,8 +82,8 @@ std::shared_ptr<AdHocConnection> AdHocConnectionImpl::connectSerial(const std::s
if (initString.size() > 0) {
serial->write(reinterpret_cast<const uint8_t *>(initString.c_str()), static_cast<int>(initString.size()));
}

return createConnection(nodeName, serial);
std::shared_ptr<Port> port = serial;
return createConnection(nodeName, port);
}

void AdHocConnectionImpl::startListening(std::shared_ptr<AdHocConnection> parent, const std::string &nodeName,
Expand Down
13 changes: 8 additions & 5 deletions MavLinkCom/src/impl/MavLinkConnectionImpl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,8 @@ std::shared_ptr<MavLinkConnection> MavLinkConnectionImpl::connectLocalUdp(const
const std::string &localAddr, int localPort) {
std::shared_ptr<UdpClientPort> socket = std::make_shared<UdpClientPort>();
socket->connect(localAddr, localPort, "", 0);
return createConnection(nodeName, socket);
std::shared_ptr<Port> port = socket;
return createConnection(nodeName, port);
}

std::shared_ptr<MavLinkConnection> MavLinkConnectionImpl::connectRemoteUdp(const std::string &nodeName,
Expand All @@ -60,7 +61,8 @@ std::shared_ptr<MavLinkConnection> MavLinkConnectionImpl::connectRemoteUdp(const
}
std::shared_ptr<UdpClientPort> socket = std::make_shared<UdpClientPort>();
socket->connect(local, 0, remoteAddr, remotePort);
return createConnection(nodeName, socket);
std::shared_ptr<Port> port = socket;
return createConnection(nodeName, port);
}

std::shared_ptr<MavLinkConnection> MavLinkConnectionImpl::connectTcp(const std::string &nodeName,
Expand All @@ -73,7 +75,8 @@ std::shared_ptr<MavLinkConnection> MavLinkConnectionImpl::connectTcp(const std::
}
std::shared_ptr<TcpClientPort> socket = std::make_shared<TcpClientPort>();
socket->connect(local, 0, remoteIpAddr, remotePort);
return createConnection(nodeName, socket);
std::shared_ptr<Port> port = socket;
return createConnection(nodeName, port);
}

std::string MavLinkConnectionImpl::acceptTcp(std::shared_ptr<MavLinkConnection> parent, const std::string &nodeName,
Expand Down Expand Up @@ -107,8 +110,8 @@ std::shared_ptr<MavLinkConnection> MavLinkConnectionImpl::connectSerial(const st
if (initString.size() > 0) {
serial->write(reinterpret_cast<const uint8_t *>(initString.c_str()), static_cast<int>(initString.size()));
}

return createConnection(nodeName, serial);
std::shared_ptr<Port> port = serial;
return createConnection(nodeName, port);
}

void MavLinkConnectionImpl::startListening(std::shared_ptr<MavLinkConnection> parent, const std::string &nodeName,
Expand Down
1 change: 1 addition & 0 deletions MavLinkCom/src/impl/MavLinkFtpClientImpl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
using namespace mavlink_utils;
using namespace mavlinkcom;
using namespace mavlinkcom_impl;

using milliseconds = std::chrono::milliseconds;

#define MAXIMUM_ROUND_TRIP_TIME 200 // 200 milliseconds should be plenty of time for single round trip to remote node.
Expand Down
4 changes: 3 additions & 1 deletion MavLinkCom/src/impl/MavLinkVehicleImpl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,10 +8,12 @@
#include "Utils.hpp"
#include <cstring>
#include <exception>

#define PACKET_PAYLOAD 253 // hard coded in MavLink code - do not change

using namespace mavlink_utils;

using namespace mavlinkcom_impl;
#define PACKET_PAYLOAD 253 // hard coded in MavLink code - do not change

void mavlink_euler_to_quaternion(float roll, float pitch, float yaw, float quaternion[4]) {
float cosPhi_2 = cosf(roll / 2);
Expand Down
1 change: 1 addition & 0 deletions MavLinkCom/src/impl/MavLinkVehicleImpl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
using namespace mavlinkcom;

namespace mavlinkcom_impl {

class MavLinkVehicleImpl : public MavLinkNodeImpl {
public:
MavLinkVehicleImpl(int localSystemId, int localComponentId);
Expand Down
1 change: 1 addition & 0 deletions MavLinkCom/src/impl/MavLinkVideoStreamImpl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
using namespace mavlinkcom;

namespace mavlinkcom_impl {

class MavLinkVideoClientImpl : public MavLinkNodeImpl {
public:
MavLinkVideoClientImpl(int localSystemId, int localComponentId);
Expand Down
1 change: 1 addition & 0 deletions MavLinkCom/src/impl/UdpSocketImpl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@

typedef int socklen_t;
static bool socket_initialized_ = false;

#else

// posix
Expand Down

0 comments on commit 6a647e1

Please sign in to comment.