From 5db9896306a0e277145675d2d02771ab2394147d Mon Sep 17 00:00:00 2001 From: Dale Phurrough Date: Sat, 18 Mar 2023 16:57:49 +0100 Subject: [PATCH] fix var hides class member, this-> in constructors - fix few compile warn 'ex' unreferenced local variable - rename setBusId() param to not hide class member - refactor XLinkConnection constructors - partial fix luxonis/depthai-core#247 --- examples/FeatureTracker/feature_tracker.cpp | 4 +-- include/depthai/pipeline/node/SPIOut.hpp | 4 +-- include/depthai/utility/LockingQueue.hpp | 5 +--- src/device/CalibrationHandler.cpp | 4 +-- src/device/DeviceBase.cpp | 10 +++---- src/device/DeviceBootloader.cpp | 18 ++++++------ src/pipeline/Node.cpp | 14 +++++----- src/pipeline/Pipeline.cpp | 8 +++--- src/pipeline/node/ColorCamera.cpp | 18 ++++++------ src/pipeline/node/MonoCamera.cpp | 6 ++-- src/pipeline/node/NeuralNetwork.cpp | 2 +- src/pipeline/node/SPIIn.cpp | 4 +-- src/utility/Initialization.cpp | 1 - src/xlink/XLinkConnection.cpp | 31 ++++++++------------- 14 files changed, 57 insertions(+), 72 deletions(-) diff --git a/examples/FeatureTracker/feature_tracker.cpp b/examples/FeatureTracker/feature_tracker.cpp index adc8647bb..422128801 100644 --- a/examples/FeatureTracker/feature_tracker.cpp +++ b/examples/FeatureTracker/feature_tracker.cpp @@ -72,9 +72,7 @@ class FeatureTrackerDrawer { } } - FeatureTrackerDrawer(std::string trackbarName, std::string windowName) { - this->trackbarName = trackbarName; - this->windowName = windowName; + FeatureTrackerDrawer(std::string trackbarName, std::string windowName) : trackbarName(trackbarName), windowName(windowName) { cv::namedWindow(windowName.c_str()); cv::createTrackbar(trackbarName.c_str(), windowName.c_str(), &trackedFeaturesPathLength, maxTrackedFeaturesPathLength, nullptr); } diff --git a/include/depthai/pipeline/node/SPIOut.hpp b/include/depthai/pipeline/node/SPIOut.hpp index 1965d3d58..ae7daa57a 100644 --- a/include/depthai/pipeline/node/SPIOut.hpp +++ b/include/depthai/pipeline/node/SPIOut.hpp @@ -43,8 +43,8 @@ class SPIOut : public NodeCRTP { * Specifies SPI Bus number to use * @param id SPI Bus id */ - void setBusId(int id) { - properties.busId = id; + void setBusId(int busId) { + properties.busId = busId; } }; diff --git a/include/depthai/utility/LockingQueue.hpp b/include/depthai/utility/LockingQueue.hpp index a40179dfb..653a01f16 100644 --- a/include/depthai/utility/LockingQueue.hpp +++ b/include/depthai/utility/LockingQueue.hpp @@ -12,10 +12,7 @@ template class LockingQueue { public: LockingQueue() = default; - explicit LockingQueue(unsigned maxSize, bool blocking = true) { - this->maxSize = maxSize; - this->blocking = blocking; - } + explicit LockingQueue(unsigned maxSize, bool blocking = true) : maxSize(maxSize), blocking(blocking) {} void setMaxSize(unsigned sz) { // Lock first diff --git a/src/device/CalibrationHandler.cpp b/src/device/CalibrationHandler.cpp index e6e2dd27a..729a778da 100644 --- a/src/device/CalibrationHandler.cpp +++ b/src/device/CalibrationHandler.cpp @@ -192,8 +192,8 @@ CalibrationHandler::CalibrationHandler(dai::Path calibrationDataPath, dai::Path camera.extrinsics.rotationMatrix[2][1] = temp; } -CalibrationHandler::CalibrationHandler(EepromData eepromData) { - this->eepromData = eepromData; +CalibrationHandler::CalibrationHandler(EepromData newEepromData) { + eepromData = newEepromData; } dai::EepromData CalibrationHandler::getEepromData() const { diff --git a/src/device/DeviceBase.cpp b/src/device/DeviceBase.cpp index 4d2fa49b8..2b8db0a24 100644 --- a/src/device/DeviceBase.cpp +++ b/src/device/DeviceBase.cpp @@ -832,7 +832,7 @@ dai::Version DeviceBase::getIMUFirmwareVersion() { try { dai::Version version = dai::Version(versionStr); return version; - } catch(const std::exception& ex) { + } catch(const std::exception&) { dai::Version version = dai::Version(0, 0, 0); return version; } @@ -844,7 +844,7 @@ dai::Version DeviceBase::getEmbeddedIMUFirmwareVersion() { try { dai::Version version = dai::Version(versionStr); return version; - } catch(const std::exception& ex) { + } catch(const std::exception&) { dai::Version version = dai::Version(0, 0, 0); return version; } @@ -1086,7 +1086,7 @@ bool DeviceBase::isEepromAvailable() { bool DeviceBase::flashCalibration(CalibrationHandler calibrationDataHandler) { try { flashCalibration2(calibrationDataHandler); - } catch(const EepromError& ex) { + } catch(const EepromError&) { return false; } return true; @@ -1118,7 +1118,7 @@ CalibrationHandler DeviceBase::readCalibration() { dai::EepromData eepromData{}; try { return readCalibration2(); - } catch(const EepromError& ex) { + } catch(const EepromError&) { // ignore - use default } return CalibrationHandler(eepromData); @@ -1182,7 +1182,7 @@ CalibrationHandler DeviceBase::readFactoryCalibrationOrDefault() { dai::EepromData eepromData{}; try { return readFactoryCalibration(); - } catch(const EepromError& ex) { + } catch(const EepromError&) { // ignore - use default } return CalibrationHandler(eepromData); diff --git a/src/device/DeviceBootloader.cpp b/src/device/DeviceBootloader.cpp index d3eb7e854..60409eda6 100644 --- a/src/device/DeviceBootloader.cpp +++ b/src/device/DeviceBootloader.cpp @@ -718,9 +718,9 @@ std::tuple DeviceBootloader::flashDepthaiApplicationPackage(s std::vector package, Memory memory) { // Bug in NETWORK bootloader in version 0.0.12 < 0.0.14 - flashing can cause a soft brick - auto version = getVersion(); - if(bootloaderType == Type::NETWORK && version < Version(0, 0, 14)) { - throw std::invalid_argument("Network bootloader requires version 0.0.14 or higher to flash applications. Current version: " + version.toString()); + auto bootloaderVersion = getVersion(); + if(bootloaderType == Type::NETWORK && bootloaderVersion < Version(0, 0, 14)) { + throw std::invalid_argument("Network bootloader requires version 0.0.14 or higher to flash applications. Current version: " + bootloaderVersion.toString()); } std::tuple ret; @@ -1102,8 +1102,8 @@ std::tuple DeviceBootloader::flashCustom( std::vector optFileData; if(!filename.empty()) { // Read file into memory first - std::ifstream stream(filename, std::ios::in | std::ios::binary); - optFileData = std::vector(std::istreambuf_iterator(stream), {}); + std::ifstream optFile(filename, std::ios::in | std::ios::binary); + optFileData = std::vector(std::istreambuf_iterator(optFile), {}); data = optFileData.data(); size = optFileData.size(); } @@ -1125,17 +1125,17 @@ std::tuple DeviceBootloader::flashCustom( result.success = 0; // TODO remove these inits after fix https://github.com/luxonis/depthai-bootloader-shared/issues/4 result.errorMsg[0] = 0; do { - std::vector data; - if(!receiveResponseData(data)) return {false, "Couldn't receive bootloader response"}; + std::vector responseData; + if(!receiveResponseData(responseData)) return {false, "Couldn't receive bootloader response"}; Response::FlashStatusUpdate update; - if(parseResponse(data, update)) { + if(parseResponse(responseData, update)) { // if progress callback is set if(progressCb != nullptr) { progressCb(update.progress); } // if flash complete response arrived, break from while loop - } else if(parseResponse(data, result)) { + } else if(parseResponse(responseData, result)) { break; } else { // Unknown response, shouldn't happen diff --git a/src/pipeline/Node.cpp b/src/pipeline/Node.cpp index d72ef4622..28aaebb23 100644 --- a/src/pipeline/Node.cpp +++ b/src/pipeline/Node.cpp @@ -91,8 +91,8 @@ void Node::Output::unlink(const Input& in) { parent.getParentPipeline().unlink(*this, in); } -void Node::Input::setBlocking(bool blocking) { - this->blocking = blocking; +void Node::Input::setBlocking(bool newBlocking) { + blocking = newBlocking; } bool Node::Input::getBlocking() const { @@ -103,7 +103,7 @@ bool Node::Input::getBlocking() const { } void Node::Input::setQueueSize(int size) { - this->queueSize = size; + queueSize = size; } int Node::Input::getQueueSize() const { @@ -113,16 +113,16 @@ int Node::Input::getQueueSize() const { return defaultQueueSize; } -void Node::Input::setWaitForMessage(bool waitForMessage) { - this->waitForMessage = waitForMessage; +void Node::Input::setWaitForMessage(bool newWaitForMessage) { + waitForMessage = newWaitForMessage; } bool Node::Input::getWaitForMessage() const { return waitForMessage.value_or(defaultWaitForMessage); } -void Node::Input::setReusePreviousMessage(bool waitForMessage) { - this->waitForMessage = !waitForMessage; +void Node::Input::setReusePreviousMessage(bool reusePreviousMessage) { + waitForMessage = !reusePreviousMessage; } bool Node::Input::getReusePreviousMessage() const { diff --git a/src/pipeline/Pipeline.cpp b/src/pipeline/Pipeline.cpp index 406455905..8f1752fac 100644 --- a/src/pipeline/Pipeline.cpp +++ b/src/pipeline/Pipeline.cpp @@ -43,8 +43,8 @@ Pipeline Pipeline::clone() const { return clone; } -Pipeline::Pipeline(const std::shared_ptr& pimpl) { - this->pimpl = pimpl; +Pipeline::Pipeline(const std::shared_ptr& newPimpl) { + pimpl = newPimpl; } GlobalProperties Pipeline::getGlobalProperties() const { @@ -304,8 +304,8 @@ void PipelineImpl::setXLinkChunkSize(int sizeBytes) { globalProperties.xlinkChunkSize = sizeBytes; } -void PipelineImpl::setBoardConfig(BoardConfig board) { - this->board = board; +void PipelineImpl::setBoardConfig(BoardConfig boardCfg) { + board = boardCfg; } BoardConfig PipelineImpl::getBoardConfig() const { diff --git a/src/pipeline/node/ColorCamera.cpp b/src/pipeline/node/ColorCamera.cpp index 729f0be2d..8f8527810 100644 --- a/src/pipeline/node/ColorCamera.cpp +++ b/src/pipeline/node/ColorCamera.cpp @@ -50,9 +50,9 @@ std::string ColorCamera::getCamera() const { } // Set which color camera to use -void ColorCamera::setCamId(int64_t id) { +void ColorCamera::setCamId(int64_t camId) { // cast to board socket - switch(id) { + switch(camId) { case 0: properties.boardSocket = CameraBoardSocket::RGB; break; @@ -66,7 +66,7 @@ void ColorCamera::setCamId(int64_t id) { properties.boardSocket = CameraBoardSocket::CAM_D; break; default: - throw std::invalid_argument(fmt::format("CamId value: {} is invalid.", id)); + throw std::invalid_argument(fmt::format("CamId value: {} is invalid.", camId)); break; } } @@ -490,12 +490,12 @@ bool ColorCamera::getPreviewKeepAspectRatio() { return properties.previewKeepAspectRatio; } -void ColorCamera::setNumFramesPool(int raw, int isp, int preview, int video, int still) { - properties.numFramesPoolRaw = raw; - properties.numFramesPoolIsp = isp; - properties.numFramesPoolPreview = preview; - properties.numFramesPoolVideo = video; - properties.numFramesPoolStill = still; +void ColorCamera::setNumFramesPool(int numRaw, int numIsp, int numPreview, int numVideo, int numStill) { + properties.numFramesPoolRaw = numRaw; + properties.numFramesPoolIsp = numIsp; + properties.numFramesPoolPreview = numPreview; + properties.numFramesPoolVideo = numVideo; + properties.numFramesPoolStill = numStill; } void ColorCamera::setPreviewNumFramesPool(int num) { diff --git a/src/pipeline/node/MonoCamera.cpp b/src/pipeline/node/MonoCamera.cpp index 47c89e246..ea979af0a 100644 --- a/src/pipeline/node/MonoCamera.cpp +++ b/src/pipeline/node/MonoCamera.cpp @@ -42,9 +42,9 @@ std::string MonoCamera::getCamera() const { } // Set which color camera to use -void MonoCamera::setCamId(int64_t id) { +void MonoCamera::setCamId(int64_t camId) { // cast to board socket - switch(id) { + switch(camId) { case 0: properties.boardSocket = CameraBoardSocket::RGB; break; @@ -58,7 +58,7 @@ void MonoCamera::setCamId(int64_t id) { properties.boardSocket = CameraBoardSocket::CAM_D; break; default: - throw std::invalid_argument(fmt::format("CamId value: {} is invalid.", id)); + throw std::invalid_argument(fmt::format("CamId value: {} is invalid.", camId)); break; } } diff --git a/src/pipeline/node/NeuralNetwork.cpp b/src/pipeline/node/NeuralNetwork.cpp index acfd6d695..aa4f0a83f 100644 --- a/src/pipeline/node/NeuralNetwork.cpp +++ b/src/pipeline/node/NeuralNetwork.cpp @@ -32,7 +32,7 @@ void NeuralNetwork::setBlob(const dai::Path& path) { } void NeuralNetwork::setBlob(OpenVINO::Blob blob) { - this->networkOpenvinoVersion = blob.version; + networkOpenvinoVersion = blob.version; auto asset = assetManager.set("__blob", std::move(blob.data)); properties.blobUri = asset->getRelativeUri(); properties.blobSize = static_cast(asset->data.size()); diff --git a/src/pipeline/node/SPIIn.cpp b/src/pipeline/node/SPIIn.cpp index 06c1d863d..5c1795a73 100644 --- a/src/pipeline/node/SPIIn.cpp +++ b/src/pipeline/node/SPIIn.cpp @@ -14,8 +14,8 @@ void SPIIn::setStreamName(const std::string& name) { properties.streamName = name; } -void SPIIn::setBusId(int id) { - properties.busId = id; +void SPIIn::setBusId(int busId) { + properties.busId = busId; } void SPIIn::setMaxDataSize(std::uint32_t maxDataSize) { diff --git a/src/utility/Initialization.cpp b/src/utility/Initialization.cpp index d111c1a95..6908c3418 100644 --- a/src/utility/Initialization.cpp +++ b/src/utility/Initialization.cpp @@ -113,7 +113,6 @@ bool initialize(const char* additionalInfo, bool installSignalHandler, void* jav xlinkGlobalHandler.protocol = X_LINK_USB_VSC; xlinkGlobalHandler.options = javavm; auto status = XLinkInitialize(&xlinkGlobalHandler); - std::string errorMsg; const auto ERROR_MSG_USB_TIP = fmt::format("If running in a container, make sure that the following is set: \"{}\"", "-v /dev/bus/usb:/dev/bus/usb --device-cgroup-rule='c 189:* rmw'"); if(X_LINK_SUCCESS != status) { diff --git a/src/xlink/XLinkConnection.cpp b/src/xlink/XLinkConnection.cpp index 5e2aa9e65..9dcbeb54f 100644 --- a/src/xlink/XLinkConnection.cpp +++ b/src/xlink/XLinkConnection.cpp @@ -277,33 +277,24 @@ DeviceInfo XLinkConnection::bootBootloader(const DeviceInfo& deviceInfo) { return DeviceInfo(foundDeviceDesc); } -XLinkConnection::XLinkConnection(const DeviceInfo& deviceDesc, std::vector mvcmdBinary, XLinkDeviceState_t expectedState) { +XLinkConnection::XLinkConnection(const DeviceInfo& deviceDesc, std::vector mvcmdBinary, XLinkDeviceState_t expectedState) + : bootWithPath(false), mvcmd(std::move(mvcmdBinary)) { initialize(); - - bootDevice = true; - bootWithPath = false; - this->mvcmd = std::move(mvcmdBinary); initDevice(deviceDesc, expectedState); } -XLinkConnection::XLinkConnection(const DeviceInfo& deviceDesc, dai::Path pathToMvcmd, XLinkDeviceState_t expectedState) { +XLinkConnection::XLinkConnection(const DeviceInfo& deviceDesc, dai::Path mvcmdPath, XLinkDeviceState_t expectedState) : pathToMvcmd(std::move(mvcmdPath)) { initialize(); - if(!pathToMvcmd.empty()) { - std::ifstream f(pathToMvcmd); - if(!f.good()) throw std::runtime_error("Error path doesn't exist. Note: Environment variables in path are not expanded. (E.g. '~', '$PATH')."); + std::ifstream testStream(pathToMvcmd); + if(!testStream.good()) throw std::runtime_error("Error path doesn't exist. Note: Environment variables in path are not expanded. (E.g. '~', '$PATH')."); } - bootDevice = true; - bootWithPath = true; - this->pathToMvcmd = std::move(pathToMvcmd); initDevice(deviceDesc, expectedState); } // Skip boot -XLinkConnection::XLinkConnection(const DeviceInfo& deviceDesc, XLinkDeviceState_t expectedState) { +XLinkConnection::XLinkConnection(const DeviceInfo& deviceDesc, XLinkDeviceState_t expectedState) : bootDevice(false) { initialize(); - - bootDevice = false; initDevice(deviceDesc, expectedState); } @@ -325,7 +316,7 @@ void XLinkConnection::close() { constexpr auto BOOTUP_SEARCH = seconds(5); if(deviceLinkId != -1 && rebootOnDestruction) { - auto tmp = deviceLinkId; + auto previousLinkId = deviceLinkId; auto ret = XLinkResetRemoteTimeout(deviceLinkId, duration_cast(RESET_TIMEOUT).count()); if(ret != X_LINK_SUCCESS) { @@ -342,17 +333,17 @@ void XLinkConnection::close() { auto t1 = steady_clock::now(); bool found = false; do { - DeviceInfo tmp; - std::tie(found, tmp) = XLinkConnection::getDeviceByMxId(deviceInfo.getMxId(), X_LINK_ANY_STATE, false); + DeviceInfo rebootingDeviceInfo; + std::tie(found, rebootingDeviceInfo) = XLinkConnection::getDeviceByMxId(deviceInfo.getMxId(), X_LINK_ANY_STATE, false); if(found) { - if(tmp.state == X_LINK_UNBOOTED || tmp.state == X_LINK_BOOTLOADER) { + if(rebootingDeviceInfo.state == X_LINK_UNBOOTED || rebootingDeviceInfo.state == X_LINK_BOOTLOADER) { break; } } } while(!found && steady_clock::now() - t1 < BOOTUP_SEARCH); } - spdlog::debug("XLinkResetRemote of linkId: ({})", tmp); + spdlog::debug("XLinkResetRemote of linkId: ({})", previousLinkId); } closed = true;