diff --git a/.drone.yml b/.drone.yml deleted file mode 100644 index a9c4673..0000000 --- a/.drone.yml +++ /dev/null @@ -1,84 +0,0 @@ -kind: pipeline -type: docker -name: build - -platform: - os: linux - arch: amd64 - -steps: - -## Run the fips "debug unittest" config -- name: build-fips-unittest - image: amarburg/lsdslam-dev-host:latest - commands: - - ./fips set config linux-make-unittest - - ./fips build - -## Run the fips "release unittest" config -- name: build-fips-release - image: amarburg/lsdslam-dev-host:latest - commands: - - ./fips set config linux-make-release-unittest - - ./fips build - -## Build with ROS melodic -# - name: build-ros-melodic -# image: amarburg/drone-ci-ros-melodic:latest -# commands: -# - wget -O- https://gitlab.com/amarburg/ros_drone_ci/-/raw/master/bootstrap.sh | /bin/bash -# environment: -# ROS_PACKAGES_TO_INSTALL: cv-bridge image-transport opencv-apps -# WSTOOL_RECURSIVE: true - -## Build with ROS noetic -- name: build-ros-noetic - image: amarburg/drone-ci-ros-noetic:latest - commands: - - wget -O- https://gitlab.com/amarburg/ros_drone_ci/-/raw/master/bootstrap.sh | /bin/bash - environment: - ROS_PACKAGES_TO_INSTALL: cv-bridge image-transport opencv-apps - WSTOOL_RECURSIVE: true - -## On success, trigger a rebuild of oculus_sonar_ros at gitlab -- name: trigger-gitlab-downstream - image: plugins/downstream - settings: - server: https://gitlab.drone.camhd.science - fork: true - token: - from_secret: gitlab_ci_token - repositories: - - apl-ocean-engineering/oculus_sonar_driver - when: - event: - exclude: - - pull_request - -## ... and all of the serdp_* packages at github -# - name: trigger-github-downstream -# image: plugins/downstream -# settings: -# server: https://github.drone.camhd.science -# fork: true -# token: -# from_secret: github_drone_token -# repositories: -# - apl-ocean-engineering/serdp_recorder -# - apl-ocean-engineering/serdp_player -# - apl-ocean-engineering/serdp_common -# when: -# event: -# exclude: -# - pull_request - -- name: slack - image: plugins/slack - settings: - webhook: - from_secret: slack_webhook - when: - status: [ success, failure ] - event: - exclude: - - pull_request diff --git a/.github/dependabot.yml b/.github/dependabot.yml new file mode 100644 index 0000000..79fc83a --- /dev/null +++ b/.github/dependabot.yml @@ -0,0 +1,6 @@ +version: 2 +updates: + - package-ecosystem: github-actions + directory: "/" + schedule: + interval: "weekly" diff --git a/.github/mergify.yml b/.github/mergify.yml new file mode 100644 index 0000000..38eb702 --- /dev/null +++ b/.github/mergify.yml @@ -0,0 +1,18 @@ +pull_request_rules: + + - name: ask to resolve conflict + conditions: + - conflict + - author!=mergify[bot] + actions: + comment: + message: This pull request is in conflict. Could you fix it @{{author}}? + + - name: development targets main branch + conditions: + - base!=main + - author!=mergify[bot] + actions: + comment: + message: | + Please target the `main` branch for development, we will backport the changes to {{base}} for you if approved and if they don't break API. diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml new file mode 100644 index 0000000..5a1a791 --- /dev/null +++ b/.github/workflows/ci.yaml @@ -0,0 +1,29 @@ +name: ROS Industrial CI + +on: + push: + branches: + - main + pull_request: + workflow_dispatch: + +jobs: + industrial-ci: + name: Run Industrial CI + + strategy: + fail-fast: false + matrix: + ros_distro: ["noetic", "kilted", "rolling"] + + steps: + - name: Checkout repository + uses: actions/checkout@v4 + with: + submodules: recursive + + - name: Run ROS Industrial CI + uses: ros-industrial/industrial_ci@master + environment: + CI_ROS_DISTRO: ${{ matrix.ros_distro }} + UPSTREAM_WORKSPACE: liboculus.repos diff --git a/.github/workflows/format.yaml b/.github/workflows/format.yaml new file mode 100644 index 0000000..2024987 --- /dev/null +++ b/.github/workflows/format.yaml @@ -0,0 +1,34 @@ +name: Formatting (pre-commit) + +on: + pull_request: + push: + branches: + - main + workflow_dispatch: + +jobs: + pre-commit: + name: Format + runs-on: ubuntu-latest + steps: + - name: Checkout repository + uses: actions/checkout@v4 + + - name: Setup Python + uses: actions/setup-python@v5 + with: + python-version: "3.10" + + - name: Install clang-format-14 + run: sudo apt-get install clang-format-14 + + - name: Run pre-commit + uses: pre-commit/action@v3.0.1 + id: precommit + + - name: Upload pre-commit changes + if: failure() && steps.precommit.outcome == 'failure' + uses: rhaschke/upload-git-patch-action@main + with: + name: pre-commit diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index a4a164f..d019757 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -1,41 +1,43 @@ -# See https://pre-commit.com for more information -# See https://pre-commit.com/hooks.html for more hooks repos: -- repo: https://github.com/pre-commit/pre-commit-hooks - rev: v3.2.0 + - repo: https://github.com/astral-sh/ruff-pre-commit + rev: v0.12.3 hooks: - - id: check-added-large-files - - id: check-json - - id: check-merge-conflict - - id: check-xml - - id: check-yaml - - id: end-of-file-fixer - - id: mixed-line-ending - - id: trailing-whitespace + # Run the linter + - id: ruff-check + args: ["--fix", "--exit-non-zero-on-fix"] + # Run the formatter. + - id: ruff-format -- repo: https://github.com/pre-commit/mirrors-clang-format - rev: v15.0.4 + - repo: https://github.com/pre-commit/mirrors-clang-format + rev: v20.1.7 hooks: - id: clang-format - # Respect .clang-format if it exists, otherwise use Google - args: ["--fallback-style=Google"] + types_or: [c++, c] -# - repo: https://gitlab.com/daverona/pre-commit/cpp -# rev: 0.8.0 -# hooks: -# - id: cpplint -# args: ["--filter=-build/include_order,-readability/todo"] - -- repo: https://github.com/psf/black - rev: 22.12.0 + # CMake formatter + - repo: https://github.com/BlankSpruce/gersemi + rev: 0.19.3 hooks: - - id: black - # For now, no configuration. May want "--line-length 80" -- repo: https://github.com/PyCQA/flake8 - rev: 6.0.0 + - id: gersemi + + - repo: https://github.com/pre-commit/pre-commit-hooks + rev: v5.0.0 hooks: - - id: flake8 - # pep8-naming catches camel_case violations - additional_dependencies: [pep8-naming, flake8-bugbear, flake8-comprehensions] - # formatting handles line-length, no reason for linter to also flag. - args: [--ignore, E501] + - id: check-added-large-files + - id: check-case-conflict + - id: check-executables-have-shebangs + - id: check-json + - id: check-merge-conflict + - id: check-shebang-scripts-are-executable + - id: check-symlinks + - id: check-toml + - id: check-xml + - id: check-yaml + - id: debug-statements + - id: destroyed-symlinks + - id: detect-private-key + - id: end-of-file-fixer + - id: fix-byte-order-marker + - id: mixed-line-ending + - id: trailing-whitespace + args: [--markdown-linebreak-ext=md] diff --git a/CMakeLists.txt b/CMakeLists.txt old mode 100755 new mode 100644 index d0d3be9..b59aded --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,108 +1,117 @@ cmake_minimum_required(VERSION 3.5) project(liboculus) -if( FIPS_CONFIG AND NOT FIPS_IMPORT ) - get_filename_component(FIPS_ROOT_DIR "../fips" ABSOLUTE) - include("${FIPS_ROOT_DIR}/cmake/fips.cmake") - - fips_setup() -else() - find_package(catkin QUIET) -endif() - # == Code common to all builds ======================================= - list(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake) -find_package( Boost REQUIRED COMPONENTS system ) - -# Actually not using full SDK, just the header files -# in thirdparty/Oculus -#find_package( OculusSDK REQUIRED ) - -if (FIPS_CONFIG) - #== fips-specific section ========================================== - add_compile_options(-std=c++17) - - ## Set global include paths - fips_include_directories( - ${CMAKE_CURRENT_SOURCE_DIR}/include - ${CMAKE_CURRENT_SOURCE_DIR}/thirdparty - ) - - ## Verbose output about ASIO handlers - #add_definitions( -DBOOST_ASIO_ENABLE_HANDLER_TRACKING ) - - fips_add_subdirectory("lib/") - - if( NOT FIPS_IMPORT ) - add_subdirectory("tools/") - endif() - - if( FIPS_UNITTESTS ) - add_subdirectory( test/ ) - endif() - - fips_finish() - +# ROS build, determine which version... +find_package(ros_environment REQUIRED) +set(ROS_VERSION $ENV{ROS_VERSION}) + +set(oculus_SRCS + lib/DataRx.cpp + lib/SonarConfiguration.cpp + lib/SonarStatus.cpp + lib/StatusRx.cpp + lib/SonarPlayer.cpp + lib/OculusMessageHandler.cpp + lib/SimpleFireMessage.cpp + lib/IoServiceThread.cpp +) + +if(${ROS_VERSION} EQUAL 2) + # == ament/ROS2 section ================================= + + find_package(ament_cmake REQUIRED) + find_package(Boost REQUIRED COMPONENTS system) + find_package(g3log_ros REQUIRED) + + set(CMAKE_CXX_STANDARD 17) + set(CMAKE_CXX_STANDARD_REQUIRED ON) + add_compile_options(-std=c++17) + + include_directories(include thirdparty) + + add_library(oculus SHARED ${oculus_SRCS}) + target_link_libraries(oculus PUBLIC Boost::system g3log_ros::g3log_ros) + + install( + TARGETS oculus + EXPORT export_${PROJECT_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin + ) + + install( + DIRECTORY include/${PROJECT_NAME}/ thirdparty/ + DESTINATION include + FILES_MATCHING + PATTERN "*.hpp" + PATTERN "*.h" + PATTERN ".git" EXCLUDE + ) + + ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET) + ament_export_include_directories(include) + ament_export_libraries(oculus) + + ament_package() +elseif(${ROS_VERSION} EQUAL 1) + # Catkin/ROS1 section ===== + find_package(catkin REQUIRED COMPONENTS g3log_ros) + find_package(Boost REQUIRED COMPONENTS system) + + catkin_package( + CATKIN_DEPENDS g3log_ros + INCLUDE_DIRS include thirdparty + LIBRARIES liboculus + ) + + add_compile_options(-std=c++14) + + add_library(liboculus ${oculus_SRCS}) + + include_directories(liboculus include thirdparty ${catkin_INCLUDE_DIRS}) + + target_link_libraries(liboculus ${catkin_LIBRARIES}) + + install( + TARGETS liboculus + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} + ) + + ## Install headers + install( + DIRECTORY include/${PROJECT_NAME}/ thirdparty/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING + PATTERN "*.hpp" + PATTERN "*.h" + PATTERN ".git" EXCLUDE + ) + + if(CATKIN_ENABLE_TESTING) + add_definitions( + -DTEST_DATA_PATH="${CMAKE_CURRENT_SOURCE_DIR}/test/data" + ) + include_directories(test/data/) + + file(GLOB oculus_test_SRCS test/unit/*cpp) + + catkin_add_gtest(oculus_test ${oculus_test_SRCS}) + + target_link_libraries( + oculus_test + ${catkin_LIBRARIES} + liboculus + Boost::system + ) + endif() else() - # == ROS / Catkin-specific section ================================= - project(liboculus) - - find_package(catkin REQUIRED - #cmake_modules - g3log_ros ) - - catkin_package( - CATKIN_DEPENDS g3log_ros - INCLUDE_DIRS include thirdparty - LIBRARIES liboculus_LIB ) - - add_compile_options(-std=c++14) - - include_directories( - include - thirdparty - ${catkin_INCLUDE_DIRS} ) - - set(oculus_SRCS - lib/DataRx.cpp - lib/SonarConfiguration.cpp - lib/SonarStatus.cpp - lib/StatusRx.cpp - lib/SonarPlayer.cpp - lib/OculusMessageHandler.cpp - lib/SimpleFireMessage.cpp - lib/IoServiceThread.cpp ) - - - add_library(liboculus_LIB ${oculus_SRCS}) - target_link_libraries(liboculus_LIB ${catkin_LIBRARIES}) - - install(TARGETS liboculus_LIB - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) - - ## Install headers - install(DIRECTORY include/${PROJECT_NAME}/ thirdparty/ - DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} - FILES_MATCHING PATTERN "*.hpp" PATTERN "*.h" - PATTERN ".git" EXCLUDE) - - if (CATKIN_ENABLE_TESTING) - add_definitions(-DTEST_DATA_PATH="${CMAKE_CURRENT_SOURCE_DIR}/test/data") - include_directories( test/data/ ) - - file(GLOB oculus_test_SRCS - test/unit/*cpp ) - - catkin_add_gtest(oculus_test ${oculus_test_SRCS}) - - target_link_libraries(oculus_test ${catkin_LIBRARIES} - liboculus_LIB - Boost::system ) - endif() - - + message( + "Unsure what sort of build to do. Not in a ROS1 or ROS2 environment" + ) endif() diff --git a/README.md b/README.md index 1f2a80e..97c77a7 100644 --- a/README.md +++ b/README.md @@ -13,7 +13,7 @@ This library contains code for: - Decoding and parsing fields from the resulting ping messages from the sonar. - Loading and parsing sonar data recorded as either: - Raw streams of binary packets. - - **Note:** This repo includes scaffold code for reading `.oculus` files saved from the Blueprint GUI, but that format is proprietary and undocumented **we cannot parse `.oculus` files.** + - **Note:** This repo includes scaffold code for reading `.oculus` files saved from the Blueprint GUI, but that format is proprietary and undocumented. **We cannot parse `.oculus` files!!** The library contains no special provisions for *saving* sonar data, but it's straightforward to write packets as a raw binary stream @@ -25,19 +25,17 @@ but it's straightforward to write packets as a raw binary stream This is a hybrid repository: -* We primarily build using catkin, though there are no ROS dependencies in the code. We hope the code is still useful for others looking to talk to the Oculus. +* We primarily build in ROS1 or ROS2, though there are no ROS dependencies in the code. We hope the code is still useful for others looking to talk to the Oculus. It is implemented as a hybrid package which should build successfully in either a ROS1 "catkin" or ROS2 "colcon" workspace. -* Historically, the repo has also supported the [fips](http://floooh.github.io/fips/) C++ dependency management tool. To build with fips: `./fips build` +* [fips](http://floooh.github.io/fips/) support has been removed from this branch. The primary dependency is on [g3log](https://github.com/KjellKod/g3log). -* If using catkin, there are two options: +* If using either ROS1 or ROS2, there are two options: * clone [g3log_ros](https://gitlab.com/apl-ocean-engineering/g3log_ros) into your workspace's `src/` directory - * use the provided `liboculus.rosinstall` file: `cd /src`; `vcs import --input liboculus/liboculus.repos` -* It will be handled automagically if using fips. + * use the provided `liboculus.rosinstall` file: `cd /src`; `vcs import --input liboculus/liboculus.repos`. The `main` branch of `g3log_ros` is also a ROS1-ROS2 hybrid. The (optional) test suite also requires Googletest and the (also optional) -binary `oc_client` requires [CLI11](https://github.com/CLIUtils/CLI11), -both of which are also handled by fips. +binary `oc_client` requires [CLI11](https://github.com/CLIUtils/CLI11). Internally, the ethernet interface uses [Boost::asio](https://www.boost.org/doc/libs/1_66_0/doc/html/boost_asio.html). @@ -119,4 +117,4 @@ Other files/classes: This code is released under the [BSD 3-clause license](LICENSE). -This repository contains one file provided by Blueprint as part of their free "Oculus Viewer" sample application ([thirdparty/Oculus/Oculus.h](thirdpart/Oculus/Oculus.h)), which describes their protocol and data formats. This file is distributed under [GPLv3](https://www.gnu.org/licenses/gpl-3.0.en.html). +This repository contains one file provided by Blueprint as part of their free "Oculus Viewer" sample application: ([thirdparty/Oculus/Oculus.h](thirdpart/Oculus/Oculus.h)). It describes their protocol and data formats. This file is distributed under [GPLv3](https://www.gnu.org/licenses/gpl-3.0.en.html). diff --git a/cmake/FindOculusSDK.cmake b/cmake/FindOculusSDK.cmake index b784d9c..c05372e 100644 --- a/cmake/FindOculusSDK.cmake +++ b/cmake/FindOculusSDK.cmake @@ -10,14 +10,13 @@ find_package(PkgConfig) -SET(TRIAL_PATHS - $ENV{OCULUS_DIR} - ${OCULUS_DIR} -) +set(TRIAL_PATHS $ENV{OCULUS_DIR} ${OCULUS_DIR}) -find_path(OCULUS_SDK_ROOT Oculus/Oculus.h - HINTS ${TRIAL_PATHS} - DOC "Location OCULUS SDK" - ) +find_path( + OCULUS_SDK_ROOT + Oculus/Oculus.h + HINTS ${TRIAL_PATHS} + DOC "Location OCULUS SDK" +) find_package_handle_standard_args(OCULUS_SDK DEFAULT_MSG OCULUS_SDK_ROOT) diff --git a/fips b/fips deleted file mode 100755 index 7b12a10..0000000 --- a/fips +++ /dev/null @@ -1,22 +0,0 @@ -#!/usr/bin/env python3 -"""fips main entry""" -import os -import sys -import subprocess - -proj_path = os.path.dirname(os.path.abspath(__file__)) -fips_path = os.path.dirname(proj_path) + "/fips" -if not os.path.isdir(fips_path): - print("\033[93m=== cloning fips build system to '{}':\033[0m".format(fips_path)) - subprocess.call(["git", "clone", "https://github.com/amarburg/fips.git", fips_path]) -sys.path.insert(0, fips_path) -try: - from mod import fips -except ImportError: - print( - "\033[91m[ERROR]\033[0m failed to initialize fips build system in '{}'".format( - proj_path - ) - ) - sys.exit(10) -fips.run(fips_path, proj_path, sys.argv) diff --git a/fips.yml b/fips.yml deleted file mode 100755 index 64b5422..0000000 --- a/fips.yml +++ /dev/null @@ -1,21 +0,0 @@ -imports: - fips-googletest: - git: https://github.com/amarburg/fips-googletest.git - cond: "FIPS_UNITTESTS" - libg3logger: - git: https://github.com/apl-ocean-engineering/libg3logger.git - CLI11-fips: - git: https://github.com/apl-ocean-engineering/CLI11-fips.git - cond: "NOT FIPS_IMPORT" ## Only needed if building tools/ - -exports: - header-dirs: - - include/ - - thirdparty/ - modules: - liboculus: . - -defines: - FIPS_EXCEPTIONS: ON - FIPS_RTTI: ON - FIPS_UNITTESTS_RUN_AFTER_BUILD: ON diff --git a/include/liboculus/BearingData.h b/include/liboculus/BearingData.h index dd268e1..fb684c6 100644 --- a/include/liboculus/BearingData.h +++ b/include/liboculus/BearingData.h @@ -30,7 +30,7 @@ #pragma once -#include // needed for CHECK macro +#include // needed for CHECK macro #include "Oculus/Oculus.h" #include "liboculus/DataTypes.h" @@ -38,7 +38,7 @@ namespace liboculus { class BearingData { - public: +public: BearingData() : _data(nullptr), _numBeams(0) { ; } BearingData(const BearingData &other) = default; @@ -64,9 +64,9 @@ class BearingData { float back() const { return _data[_numBeams - 1] / 100.0; } - private: +private: const int16_t *_data; uint16_t _numBeams; }; -} // namespace liboculus +} // namespace liboculus diff --git a/include/liboculus/Constants.h b/include/liboculus/Constants.h index 33297b6..299e7ac 100644 --- a/include/liboculus/Constants.h +++ b/include/liboculus/Constants.h @@ -33,7 +33,7 @@ #pragma once #include -#include // for size_t +#include // for size_t #include #include @@ -62,7 +62,7 @@ const float AzimuthBeamwidthDeg = 1.0; const float AzimuthBeamwidthRad = DEG2RAD(AzimuthBeamwidthDeg); const float MaxRange = 120; -}; // namespace Freq_750kHz +}; // namespace Freq_750kHz namespace Freq_1200kHz { const float ElevationBeamwidthDeg = 12.0; @@ -72,8 +72,8 @@ const float AzimuthBeamwidthDeg = 0.6; const float AzimuthBeamwidthRad = DEG2RAD(AzimuthBeamwidthDeg); const float MaxRange = 40; -}; // namespace Freq_1200kHz -}; // namespace Oculus_M750d +}; // namespace Freq_1200kHz +}; // namespace Oculus_M750d namespace Oculus_M1200d { namespace Freq_1200kHz { @@ -84,7 +84,7 @@ const float AzimuthBeamwidthDeg = 0.6; const float AzimuthBeamwidthRad = DEG2RAD(AzimuthBeamwidthDeg); const float MaxRange = 40; -}; // namespace Freq_1200kHz +}; // namespace Freq_1200kHz namespace Freq_2100kHz { const float ElevationBeamwidthDeg = 12.0; @@ -94,8 +94,8 @@ const float AzimuthBeamwidthDeg = 0.4; const float AzimuthBeamwidthRad = DEG2RAD(AzimuthBeamwidthDeg); const float MaxRange = 10; -}; // namespace Freq_2100kHz -}; // namespace Oculus_M1200d +}; // namespace Freq_2100kHz +}; // namespace Oculus_M1200d namespace Oculus_M3000d { namespace Freq_1200kHz { @@ -106,7 +106,7 @@ const float AzimuthBeamwidthDeg = 0.6; const float AzimuthBeamwidthRad = DEG2RAD(AzimuthBeamwidthDeg); const float MaxRange = 30; -}; // namespace Freq_1200kHz +}; // namespace Freq_1200kHz namespace Freq_3000kHz { const float ElevationBeamwidthDeg = 20.0; @@ -116,8 +116,8 @@ const float AzimuthBeamwidthDeg = 0.4; const float AzimuthBeamwidthRad = DEG2RAD(AzimuthBeamwidthDeg); const float MaxRange = 5; -}; // namespace Freq_3000kHz -}; // namespace Oculus_M3000d +}; // namespace Freq_3000kHz +}; // namespace Oculus_M3000d //=================================================================== // @@ -153,4 +153,4 @@ struct FlagBits { // liboculus/thirdparty/Oculus/Oculus.h. typedef enum { OCULUS_LOW_FREQ = 1, OCULUS_HIGH_FREQ = 2 } OculusFreqMode; -} // namespace liboculus +} // namespace liboculus diff --git a/include/liboculus/DataRx.h b/include/liboculus/DataRx.h index 3e9738b..e464799 100644 --- a/include/liboculus/DataRx.h +++ b/include/liboculus/DataRx.h @@ -45,7 +45,7 @@ namespace liboculus { using std::shared_ptr; class DataRx : public OculusMessageHandler { - public: +public: explicit DataRx(const IoServiceThread::IoContextPtr &iosrv); ~DataRx(); @@ -72,7 +72,7 @@ class DataRx : public OculusMessageHandler { virtual void haveWritten(const ByteVector &bytes) { ; } virtual void haveRead(const ByteVector &bytes) { ; } - private: +private: void onConnect(const boost::system::error_code &error); // Initiates a network read. @@ -106,9 +106,9 @@ class DataRx : public OculusMessageHandler { OnConnectCallback _onConnectCallback; -}; // class DataRx +}; // class DataRx -template +template void DataRx::sendSimpleFireMessage(const SonarConfiguration &config) { if (!isConnected()) { LOG(WARNING) << "Can't send to sonar, not connected"; @@ -128,4 +128,4 @@ void DataRx::sendSimpleFireMessage(const SonarConfiguration &config) { } } -} // namespace liboculus +} // namespace liboculus diff --git a/include/liboculus/DataTypes.h b/include/liboculus/DataTypes.h index 3e56043..1b43b00 100644 --- a/include/liboculus/DataTypes.h +++ b/include/liboculus/DataTypes.h @@ -33,7 +33,7 @@ #pragma once #include -#include // for size_t +#include // for size_t #include #include @@ -43,21 +43,18 @@ namespace liboculus { typedef std::vector ByteVector; -template -T deg2rad(const T &value) { - return M_PI / 180.0 * value; -} +template T deg2rad(const T &value) { return M_PI / 180.0 * value; } inline const char *DataSizeToString(DataSizeType d) { switch (d) { - case dataSize8Bit: - return "8-bit"; - case dataSize16Bit: - return "16-bit"; - case dataSize24Bit: - return "24-bit"; - case dataSize32Bit: - return "32-bit"; + case dataSize8Bit: + return "8-bit"; + case dataSize16Bit: + return "16-bit"; + case dataSize24Bit: + return "24-bit"; + case dataSize32Bit: + return "32-bit"; } return "unknown"; @@ -65,14 +62,14 @@ inline const char *DataSizeToString(DataSizeType d) { inline size_t SizeOfDataSize(DataSizeType d) { switch (d) { - case dataSize8Bit: - return 1; - case dataSize16Bit: - return 2; - case dataSize24Bit: - return 3; - case dataSize32Bit: - return 4; + case dataSize8Bit: + return 1; + case dataSize16Bit: + return 2; + case dataSize24Bit: + return 3; + case dataSize32Bit: + return 4; } return 0; @@ -82,18 +79,18 @@ inline size_t SizeOfDataSize(DataSizeType d) { inline const char *MessageTypeToString(OculusMessageType t) { switch (t) { - case messageSimpleFire: - return "messageSimpleFire"; - case messagePingResult: - return "messagePingResult"; - case messageSimplePingResult: - return "messageSimplePingResult"; - case messageUserConfig: - return "messageUserConfig"; - case messageLogs: - return "messageLogs"; - case messageDummy: - return "messageDummy"; + case messageSimpleFire: + return "messageSimpleFire"; + case messagePingResult: + return "messagePingResult"; + case messageSimplePingResult: + return "messageSimplePingResult"; + case messageUserConfig: + return "messageUserConfig"; + case messageLogs: + return "messageLogs"; + case messageDummy: + return "messageDummy"; } return "(unknown)"; @@ -103,18 +100,18 @@ inline const char *MessageTypeToString(OculusMessageType t) { inline unsigned int PingRateToHz(PingRateType p) { switch (p) { - case pingRateNormal: - return 10; - case pingRateHigh: - return 15; - case pingRateHighest: - return 40; - case pingRateLow: - return 5; - case pingRateLowest: - return 2; - case pingRateStandby: - return 0; + case pingRateNormal: + return 10; + case pingRateHigh: + return 15; + case pingRateHighest: + return 40; + case pingRateLow: + return 5; + case pingRateLowest: + return 2; + case pingRateStandby: + return 0; } return -1; @@ -134,4 +131,4 @@ inline std::string FreqModeToString(uint8_t mode) { return "(unknown)"; } -} // namespace liboculus +} // namespace liboculus diff --git a/include/liboculus/GainData.h b/include/liboculus/GainData.h index becd393..573330b 100644 --- a/include/liboculus/GainData.h +++ b/include/liboculus/GainData.h @@ -32,7 +32,7 @@ #include -#include // needed for CHECK macro +#include // needed for CHECK macro #include #include @@ -43,9 +43,8 @@ namespace liboculus { // \todo A long-term TODO: ImageData, GainData and BearingData are all // fairly similar in functionality, could reduce the DRY? -template -class GainData { - public: +template class GainData { +public: typedef T DataType; GainData() : _data() { ; } @@ -75,8 +74,8 @@ class GainData { T operator[](unsigned int i) const { return at(i); } - private: +private: std::vector _data; }; -} // namespace liboculus +} // namespace liboculus diff --git a/include/liboculus/ImageData.h b/include/liboculus/ImageData.h index 9619427..1d4b506 100644 --- a/include/liboculus/ImageData.h +++ b/include/liboculus/ImageData.h @@ -33,7 +33,7 @@ #pragma once -#include // needed for CHECK macro +#include // needed for CHECK macro #include #include "DataTypes.h" @@ -42,28 +42,20 @@ namespace liboculus { class ImageData { - public: +public: ImageData() - : _data(nullptr), - _dataSize(0), - _imageSize(0), - _numRanges(0), - _numBeams(0), - _stride(0), - _offset(0) {} + : _data(nullptr), _dataSize(0), _imageSize(0), _numRanges(0), + _numBeams(0), _stride(0), _offset(0) {} ImageData(const ImageData &other) = default; ImageData(const uint8_t *data, uint32_t imageSize, uint16_t nRanges, uint16_t nBeams, uint8_t dataSize, uint16_t stride = 0, uint16_t offset = 0) - : _data(data), - _dataSize(dataSize), - _imageSize(imageSize), - _numRanges(nRanges), - _numBeams(nBeams), + : _data(data), _dataSize(dataSize), _imageSize(imageSize), + _numRanges(nRanges), _numBeams(nBeams), _stride(stride == 0 ? nBeams * dataSize - : stride), // Stride is in _bytes_ + : stride), // Stride is in _bytes_ _offset(offset) {} uint16_t nRanges() const { return _numRanges; } @@ -124,11 +116,11 @@ class ImageData { return 0; } - private: +private: const uint8_t *_data; uint8_t _dataSize; uint32_t _imageSize; size_t _numRanges, _numBeams, _stride, _offset; -}; // class ImageData +}; // class ImageData -} // namespace liboculus +} // namespace liboculus diff --git a/include/liboculus/IoServiceThread.h b/include/liboculus/IoServiceThread.h index 7a2c9b9..a2dcd33 100644 --- a/include/liboculus/IoServiceThread.h +++ b/include/liboculus/IoServiceThread.h @@ -41,7 +41,7 @@ namespace liboculus { // Generic "worker thread" for boost::asio class IoServiceThread { - public: +public: #if BOOST_VERSION >= 106600 typedef boost::asio::io_context IoContext; #else @@ -60,7 +60,7 @@ class IoServiceThread { const IoContextPtr &context() { return _context; } - private: +private: IoContextPtr _context; #if BOOST_VERSION >= 106600 @@ -76,4 +76,4 @@ class IoServiceThread { void threadExec(); }; -} // namespace liboculus +} // namespace liboculus diff --git a/include/liboculus/MessageHeader.h b/include/liboculus/MessageHeader.h index 0fe89cc..90a6625 100644 --- a/include/liboculus/MessageHeader.h +++ b/include/liboculus/MessageHeader.h @@ -51,7 +51,7 @@ using std::vector; // by the buffer. Other packet types can inherit from this class // to represent large structs which start with a MessageHeader class MessageHeader { - public: +public: MessageHeader() = default; MessageHeader(const MessageHeader &) = default; @@ -76,7 +76,7 @@ class MessageHeader { } virtual bool valid() const { - return hdr()->oculusId == OCULUS_CHECK_ID; // 0x4f53 + return hdr()->oculusId == OCULUS_CHECK_ID; // 0x4f53 } virtual void dump() const { @@ -95,8 +95,8 @@ class MessageHeader { const std::shared_ptr &buffer(void) const { return _buffer; } - protected: +protected: std::shared_ptr _buffer; -}; // class MessageHeader +}; // class MessageHeader -} // namespace liboculus +} // namespace liboculus diff --git a/include/liboculus/OculusMessageHandler.h b/include/liboculus/OculusMessageHandler.h index 7891843..b11cc65 100644 --- a/include/liboculus/OculusMessageHandler.h +++ b/include/liboculus/OculusMessageHandler.h @@ -47,17 +47,14 @@ using std::shared_ptr; // and will call callbacks when it happens. // Both DataRx and SonarPlay inherit from this class. class OculusMessageHandler { - public: +public: OculusMessageHandler() : _simplePingCallback(), _simplePing2Callback() { ; } - template - using Callback = std::function; + template using Callback = std::function; - template - void setCallback(Callback callback); + template void setCallback(Callback callback); - template - void callback(const T &); + template void callback(const T &); typedef Callback SimplePingCallback; typedef Callback SimplePing2Callback; @@ -68,4 +65,4 @@ class OculusMessageHandler { SimplePing2Callback _simplePing2Callback; }; -} // namespace liboculus +} // namespace liboculus diff --git a/include/liboculus/PingAgreesWithConfig.h b/include/liboculus/PingAgreesWithConfig.h index 4ccc2f1..2947ba2 100644 --- a/include/liboculus/PingAgreesWithConfig.h +++ b/include/liboculus/PingAgreesWithConfig.h @@ -67,4 +67,4 @@ bool checkPingAgreesWithConfig(const SimplePingResult &ping, return true; } -} // namespace liboculus +} // namespace liboculus diff --git a/include/liboculus/SimpleFireMessage.h b/include/liboculus/SimpleFireMessage.h index 2e3c95a..5af9e4b 100644 --- a/include/liboculus/SimpleFireMessage.h +++ b/include/liboculus/SimpleFireMessage.h @@ -48,7 +48,7 @@ using std::vector; // A simple parser of flag bytes class OculusSimpleFireFlags { - public: +public: OculusSimpleFireFlags() = delete; OculusSimpleFireFlags(const uint8_t flags) : _data(flags) { ; } @@ -59,13 +59,12 @@ class OculusSimpleFireFlags { bool getGainAssistance() const { return _data & FlagBits::GainAssistance; } bool get512Beams() const { return _data & FlagBits::Do512Beams; } - private: +private: uint8_t _data; }; -template -class SimpleFireMessage : public MessageHeader { - public: +template class SimpleFireMessage : public MessageHeader { +public: SimpleFireMessage() = default; SimpleFireMessage(const SimpleFireMessage &other) = default; @@ -83,9 +82,9 @@ class SimpleFireMessage : public MessageHeader { float range() const; - protected: +protected: OculusSimpleFireFlags _flags; -}; // class SimpleFireMessage +}; // class SimpleFireMessage template SimpleFireMessage::SimpleFireMessage( @@ -94,8 +93,7 @@ SimpleFireMessage::SimpleFireMessage( assert(buffer->size() >= sizeof(FireMsgT)); } -template -void SimpleFireMessage::dump() const { +template void SimpleFireMessage::dump() const { MessageHeader::dump(); LOG(DEBUG) << " Mode: " @@ -118,4 +116,4 @@ void SimpleFireMessage::dump() const { LOG(DEBUG) << " Gain pct: " << this->fireMsg()->gainPercent; } -} // namespace liboculus +} // namespace liboculus diff --git a/include/liboculus/SimplePingResult.h b/include/liboculus/SimplePingResult.h index cbbfa44..bb90761 100644 --- a/include/liboculus/SimplePingResult.h +++ b/include/liboculus/SimplePingResult.h @@ -62,7 +62,7 @@ using std::vector; template class SimplePingResult : public SimpleFireMessage { - public: +public: typedef SimpleFireMessage SimpleFireMsg_t; typedef GainData GainData_t; @@ -84,13 +84,13 @@ class SimplePingResult : public SimpleFireMessage { bool valid() const override; void dump() const override; - private: +private: // Objects which create OOI overlays the _buffer for easier interpretation BearingData _bearings; GainData_t _gains; ImageData _image; -}; // class SimplePingResult +}; // class SimplePingResult typedef SimplePingResult SimplePingResultV1; typedef SimplePingResult SimplePingResultV2; @@ -138,10 +138,11 @@ const Ping_t *SimplePingResult::ping() const { return reinterpret_cast(this->buffer()->data()); } -template -bool SimplePingResult::valid() const { - if (this->buffer()->size() < sizeof(OculusMessageHeader)) return false; - if (this->buffer()->size() < this->packetSize()) return false; +template bool SimplePingResult::valid() const { + if (this->buffer()->size() < sizeof(OculusMessageHeader)) + return false; + if (this->buffer()->size() < this->packetSize()) + return false; if (!MessageHeader::valid()) { LOG(WARNING) << "Header not valid"; @@ -165,8 +166,7 @@ bool SimplePingResult::valid() const { return true; } -template -void SimplePingResult::dump() const { +template void SimplePingResult::dump() const { LOG(DEBUG) << "--------------"; SimpleFireMsg_t::dump(); @@ -200,4 +200,4 @@ void SimplePingResult::dump() const { LOG(DEBUG) << "--------------"; } -} // namespace liboculus +} // namespace liboculus diff --git a/include/liboculus/SonarConfiguration.h b/include/liboculus/SonarConfiguration.h index be3ee27..ce3385e 100644 --- a/include/liboculus/SonarConfiguration.h +++ b/include/liboculus/SonarConfiguration.h @@ -44,11 +44,10 @@ namespace liboculus { // the shadow copy of the SimpleFireMessage{2}, instead // just make it at time of serialization. class SonarConfiguration { - public: +public: SonarConfiguration(); - template - std::vector serialize() const; + template std::vector serialize() const; // Setter functions SonarConfiguration &setGamma(int input); @@ -96,7 +95,7 @@ class SonarConfiguration { void dump() const; - private: +private: void updateFlags() const; typedef OculusSimpleFireMessage2 ConfigFireMessage; @@ -112,6 +111,6 @@ class SonarConfiguration { DataSizeType _dataSize; -}; // class SonarConfiguration +}; // class SonarConfiguration -} // namespace liboculus +} // namespace liboculus diff --git a/include/liboculus/SonarPlayer.h b/include/liboculus/SonarPlayer.h index bb2a3c6..bd17f00 100644 --- a/include/liboculus/SonarPlayer.h +++ b/include/liboculus/SonarPlayer.h @@ -40,7 +40,7 @@ namespace liboculus { class SonarPlayerBase : public OculusMessageHandler { - public: +public: // typedef tl::expected, bool> SonarPlayerResult_t; SonarPlayerBase() { ; } @@ -63,7 +63,7 @@ class SonarPlayerBase : public OculusMessageHandler { // static std::shared_ptr createGPMFSonarPlayer(); // #endif - protected: +protected: std::ifstream _input; }; @@ -71,14 +71,14 @@ class SonarPlayerBase : public OculusMessageHandler { /// /// class RawSonarPlayer : public SonarPlayerBase { - public: +public: RawSonarPlayer() : SonarPlayerBase() { ; } virtual ~RawSonarPlayer() { ; } bool nextPing() override; - private: +private: }; -} // namespace liboculus +} // namespace liboculus diff --git a/include/liboculus/SonarStatus.h b/include/liboculus/SonarStatus.h index 6ac6414..6804d6d 100644 --- a/include/liboculus/SonarStatus.h +++ b/include/liboculus/SonarStatus.h @@ -44,14 +44,14 @@ namespace liboculus { /// Thin wrapper around OculusStatusMsg class SonarStatus { - public: +public: SonarStatus(const ByteVector &buffer); const OculusStatusMsg *msg(void) const { return reinterpret_cast(_buffer.data()); } - bool valid() const { return true; } // todo: actually validate the packet + bool valid() const { return true; } // todo: actually validate the packet // Print most recent OculusStatusMsg to LOG(DEBUG) void dump() const; @@ -59,8 +59,8 @@ class SonarStatus { boost::asio::ip::address ipAddr() const; uint32_t status() const { return msg()->status; } - private: +private: const ByteVector &_buffer; }; -} // namespace liboculus +} // namespace liboculus diff --git a/include/liboculus/StatusRx.h b/include/liboculus/StatusRx.h index 45c5f46..1d7e7f9 100644 --- a/include/liboculus/StatusRx.h +++ b/include/liboculus/StatusRx.h @@ -49,7 +49,7 @@ using boost::asio::ip::udp; // // class StatusRx { - public: +public: explicit StatusRx(const IoServiceThread::IoContextPtr &iosrv); ~StatusRx() {} @@ -60,7 +60,7 @@ class StatusRx { _sonarStatusCallback = callback; } - private: +private: void doConnect(); void scheduleRead(); @@ -72,8 +72,8 @@ class StatusRx { std::vector _buffer; // uint16_t _port; // Port to listen on - uint16_t _num_valid_rx; // Number of valid status messages - uint16_t _num_invalid_rx; // Number of invalid status messages + uint16_t _num_valid_rx; // Number of valid status messages + uint16_t _num_invalid_rx; // Number of invalid status messages udp::socket _socket; @@ -82,4 +82,4 @@ class StatusRx { SonarStatusCallback _sonarStatusCallback; }; -} // namespace liboculus +} // namespace liboculus diff --git a/include/liboculus/expected.hpp b/include/liboculus/expected.hpp index 91889dd..f7c125d 100644 --- a/include/liboculus/expected.hpp +++ b/include/liboculus/expected.hpp @@ -36,34 +36,34 @@ #define TL_EXPECTED_MSVC2015_CONSTEXPR constexpr #endif -#if (defined(__GNUC__) && __GNUC__ == 4 && __GNUC_MINOR__ <= 9 && \ +#if (defined(__GNUC__) && __GNUC__ == 4 && __GNUC_MINOR__ <= 9 && \ !defined(__clang__)) #define TL_EXPECTED_GCC49 #endif -#if (defined(__GNUC__) && __GNUC__ == 5 && __GNUC_MINOR__ <= 4 && \ +#if (defined(__GNUC__) && __GNUC__ == 5 && __GNUC_MINOR__ <= 4 && \ !defined(__clang__)) #define TL_EXPECTED_GCC54 #endif -#if (defined(__GNUC__) && __GNUC__ == 5 && __GNUC_MINOR__ <= 5 && \ +#if (defined(__GNUC__) && __GNUC__ == 5 && __GNUC_MINOR__ <= 5 && \ !defined(__clang__)) #define TL_EXPECTED_GCC55 #endif -#if (defined(__GNUC__) && __GNUC__ == 4 && __GNUC_MINOR__ <= 9 && \ +#if (defined(__GNUC__) && __GNUC__ == 4 && __GNUC_MINOR__ <= 9 && \ !defined(__clang__)) // GCC < 5 doesn't support overloading on const&& for member functions #define TL_EXPECTED_NO_CONSTRR // GCC < 5 doesn't support some standard C++11 type traits -#define TL_EXPECTED_IS_TRIVIALLY_COPY_CONSTRUCTIBLE(T) \ +#define TL_EXPECTED_IS_TRIVIALLY_COPY_CONSTRUCTIBLE(T) \ std::has_trivial_copy_constructor -#define TL_EXPECTED_IS_TRIVIALLY_COPY_ASSIGNABLE(T) \ +#define TL_EXPECTED_IS_TRIVIALLY_COPY_ASSIGNABLE(T) \ std::has_trivial_copy_assign // This one will be different for GCC 5.7 if it's ever supported -#define TL_EXPECTED_IS_TRIVIALLY_DESTRUCTIBLE(T) \ +#define TL_EXPECTED_IS_TRIVIALLY_DESTRUCTIBLE(T) \ std::is_trivially_destructible // GCC 5 < v < 8 has a bug in is_trivially_copy_constructible which breaks @@ -80,22 +80,22 @@ struct is_trivially_copy_constructible template struct is_trivially_copy_constructible> : std::false_type {}; #endif -} // namespace detail -} // namespace tl +} // namespace detail +} // namespace tl #endif -#define TL_EXPECTED_IS_TRIVIALLY_COPY_CONSTRUCTIBLE(T) \ +#define TL_EXPECTED_IS_TRIVIALLY_COPY_CONSTRUCTIBLE(T) \ tl::detail::is_trivially_copy_constructible -#define TL_EXPECTED_IS_TRIVIALLY_COPY_ASSIGNABLE(T) \ +#define TL_EXPECTED_IS_TRIVIALLY_COPY_ASSIGNABLE(T) \ std::is_trivially_copy_assignable -#define TL_EXPECTED_IS_TRIVIALLY_DESTRUCTIBLE(T) \ +#define TL_EXPECTED_IS_TRIVIALLY_DESTRUCTIBLE(T) \ std::is_trivially_destructible #else -#define TL_EXPECTED_IS_TRIVIALLY_COPY_CONSTRUCTIBLE(T) \ +#define TL_EXPECTED_IS_TRIVIALLY_COPY_CONSTRUCTIBLE(T) \ std::is_trivially_copy_constructible -#define TL_EXPECTED_IS_TRIVIALLY_COPY_ASSIGNABLE(T) \ +#define TL_EXPECTED_IS_TRIVIALLY_COPY_ASSIGNABLE(T) \ std::is_trivially_copy_assignable -#define TL_EXPECTED_IS_TRIVIALLY_DESTRUCTIBLE(T) \ +#define TL_EXPECTED_IS_TRIVIALLY_DESTRUCTIBLE(T) \ std::is_trivially_destructible #endif @@ -109,7 +109,7 @@ struct is_trivially_copy_constructible> : std::false_type {}; #define TL_EXPECTED_GCC49_CONSTEXPR constexpr #endif -#if (__cplusplus == 201103L || defined(TL_EXPECTED_MSVC2015) || \ +#if (__cplusplus == 201103L || defined(TL_EXPECTED_MSVC2015) || \ defined(TL_EXPECTED_GCC49)) #define TL_EXPECTED_11_CONSTEXPR #else @@ -117,8 +117,7 @@ struct is_trivially_copy_constructible> : std::false_type {}; #endif namespace tl { -template -class expected; +template class expected; #ifndef TL_MONOSTATE_INPLACE_MUTEX #define TL_MONOSTATE_INPLACE_MUTEX @@ -130,9 +129,8 @@ struct in_place_t { static constexpr in_place_t in_place{}; #endif -template -class unexpected { - public: +template class unexpected { +public: static_assert(!std::is_same::value, "E must not be void"); unexpected() = delete; @@ -145,7 +143,7 @@ class unexpected { TL_EXPECTED_11_CONSTEXPR E &&value() && { return std::move(m_val); } constexpr const E &&value() const && { return std::move(m_val); } - private: +private: E m_val; }; @@ -201,22 +199,18 @@ template #ifndef TL_TRAITS_MUTEX #define TL_TRAITS_MUTEX // C++14-style aliases for brevity -template -using remove_const_t = typename std::remove_const::type; +template using remove_const_t = typename std::remove_const::type; template using remove_reference_t = typename std::remove_reference::type; -template -using decay_t = typename std::decay::type; +template using decay_t = typename std::decay::type; template using enable_if_t = typename std::enable_if::type; template using conditional_t = typename std::conditional::type; // std::conjunction from C++17 -template -struct conjunction : std::true_type {}; -template -struct conjunction : B {}; +template struct conjunction : std::true_type {}; +template struct conjunction : B {}; template struct conjunction : std::conditional, B>::type {}; @@ -250,12 +244,9 @@ template struct is_pointer_to_non_const_member_func : std::true_type {}; -template -struct is_const_or_const_ref : std::false_type {}; -template -struct is_const_or_const_ref : std::true_type {}; -template -struct is_const_or_const_ref : std::true_type {}; +template struct is_const_or_const_ref : std::false_type {}; +template struct is_const_or_const_ref : std::true_type {}; +template struct is_const_or_const_ref : std::true_type {}; #endif // std::invoke from C++17 @@ -282,8 +273,7 @@ constexpr auto invoke(Fn &&f, Args &&...args) noexcept( } // std::invoke_result from C++17 -template -struct invoke_result_impl; +template struct invoke_result_impl; template struct invoke_result_impl< @@ -302,11 +292,9 @@ using invoke_result_t = typename invoke_result::type; #if defined(_MSC_VER) && _MSC_VER <= 1900 // TODO make a version which works with MSVC 2015 -template -struct is_swappable : std::true_type {}; +template struct is_swappable : std::true_type {}; -template -struct is_nothrow_swappable : std::true_type {}; +template struct is_nothrow_swappable : std::true_type {}; #else // https://stackoverflow.com/questions/26744589/what-is-a-proper-way-to-implement-is-swappable-to-test-for-the-swappable-concept namespace swap_adl_tests { @@ -314,22 +302,18 @@ namespace swap_adl_tests { // signature) struct tag {}; -template -tag swap(T &, T &); -template -tag swap(T (&a)[N], T (&b)[N]); +template tag swap(T &, T &); +template tag swap(T (&a)[N], T (&b)[N]); // helper functions to test if an unqualified swap is possible, and if it // becomes std::swap -template -std::false_type can_swap(...) noexcept(false); +template std::false_type can_swap(...) noexcept(false); template (), std::declval()))> std::true_type can_swap(int) noexcept(noexcept(swap(std::declval(), std::declval()))); -template -std::false_type uses_std(...); +template std::false_type uses_std(...); template std::is_same(), std::declval())), tag> uses_std(int); @@ -346,7 +330,7 @@ struct is_std_swap_noexcept : is_std_swap_noexcept {}; template struct is_adl_swap_noexcept : std::integral_constant(0))> {}; -} // namespace swap_adl_tests +} // namespace swap_adl_tests template struct is_swappable @@ -379,12 +363,10 @@ struct is_nothrow_swappable #endif // Trait for checking if a type is a tl::expected -template -struct is_expected_impl : std::false_type {}; +template struct is_expected_impl : std::false_type {}; template struct is_expected_impl> : std::true_type {}; -template -using is_expected = is_expected_impl>; +template using is_expected = is_expected_impl>; template using expected_enable_forward_value = detail::enable_if_t< @@ -423,7 +405,7 @@ using is_copy_assignable_or_void = is_void_or>; template using is_move_assignable_or_void = is_void_or>; -} // namespace detail +} // namespace detail namespace detail { struct no_init_t {}; @@ -484,8 +466,7 @@ struct expected_storage_base { // This specialization is for when both `T` and `E` are trivially-destructible, // so the destructor of the `expected` can be trivial. -template -struct expected_storage_base { +template struct expected_storage_base { constexpr expected_storage_base() : m_val(T{}), m_has_val(true) {} constexpr expected_storage_base(no_init_t) : m_no_init(), m_has_val(false) {} @@ -525,8 +506,7 @@ struct expected_storage_base { }; // T is trivial, E is not. -template -struct expected_storage_base { +template struct expected_storage_base { constexpr expected_storage_base() : m_val(T{}), m_has_val(true) {} TL_EXPECTED_MSVC2015_CONSTEXPR expected_storage_base(no_init_t) : m_no_init(), m_has_val(false) {} @@ -572,8 +552,7 @@ struct expected_storage_base { }; // E is trivial, T is not. -template -struct expected_storage_base { +template struct expected_storage_base { constexpr expected_storage_base() : m_val(T{}), m_has_val(true) {} constexpr expected_storage_base(no_init_t) : m_no_init(), m_has_val(false) {} @@ -617,8 +596,7 @@ struct expected_storage_base { }; // `T` is `void`, `E` is trivially-destructible -template -struct expected_storage_base { +template struct expected_storage_base { TL_EXPECTED_MSVC2015_CONSTEXPR expected_storage_base() : m_has_val(true) {} constexpr expected_storage_base(no_init_t) : m_val(), m_has_val(false) {} @@ -648,8 +626,7 @@ struct expected_storage_base { }; // `T` is `void`, `E` is not trivially-destructible -template -struct expected_storage_base { +template struct expected_storage_base { constexpr expected_storage_base() : m_dummy(), m_has_val(true) {} constexpr expected_storage_base(no_init_t) : m_dummy(), m_has_val(false) {} @@ -688,20 +665,17 @@ template struct expected_operations_base : expected_storage_base { using expected_storage_base::expected_storage_base; - template - void construct(Args &&...args) noexcept { + template void construct(Args &&...args) noexcept { new (std::addressof(this->m_val)) T(std::forward(args)...); this->m_has_val = true; } - template - void construct_with(Rhs &&rhs) noexcept { + template void construct_with(Rhs &&rhs) noexcept { new (std::addressof(this->m_val)) T(std::forward(rhs).get()); this->m_has_val = true; } - template - void construct_error(Args &&...args) noexcept { + template void construct_error(Args &&...args) noexcept { new (std::addressof(this->m_unexpect)) unexpected(std::forward(args)...); this->m_has_val = false; @@ -831,8 +805,7 @@ struct expected_operations_base : expected_storage_base { #endif // The common part of move/copy assigning - template - void assign_common(Rhs &&rhs) { + template void assign_common(Rhs &&rhs) { if (this->m_has_val) { if (rhs.m_has_val) { get() = std::forward(rhs).get(); @@ -878,27 +851,21 @@ template struct expected_operations_base : expected_storage_base { using expected_storage_base::expected_storage_base; - template - void construct() noexcept { - this->m_has_val = true; - } + template void construct() noexcept { this->m_has_val = true; } // This function doesn't use its argument, but needs it so that code in // levels above this can work independently of whether T is void - template - void construct_with(Rhs &&) noexcept { + template void construct_with(Rhs &&) noexcept { this->m_has_val = true; } - template - void construct_error(Args &&...args) noexcept { + template void construct_error(Args &&...args) noexcept { new (std::addressof(this->m_unexpect)) unexpected(std::forward(args)...); this->m_has_val = false; } - template - void assign(Rhs &&rhs) noexcept { + template void assign(Rhs &&rhs) noexcept { if (!this->m_has_val) { if (rhs.m_has_val) { geterr().~unexpected(); @@ -936,8 +903,9 @@ struct expected_operations_base : expected_storage_base { // This class manages conditionally having a trivial copy constructor // This specialization is for when T and E are trivially copy constructible template :: - value &&TL_EXPECTED_IS_TRIVIALLY_COPY_CONSTRUCTIBLE(E)::value> + bool = is_void_or::value && + TL_EXPECTED_IS_TRIVIALLY_COPY_CONSTRUCTIBLE(E)::value> struct expected_copy_base : expected_operations_base { using expected_operations_base::expected_operations_base; }; @@ -969,14 +937,14 @@ struct expected_copy_base : expected_operations_base { // move constructible #ifndef TL_EXPECTED_GCC49 template >::value - &&std::is_trivially_move_constructible::value> + bool = + is_void_or>::value && + std::is_trivially_move_constructible::value> struct expected_move_base : expected_copy_base { using expected_copy_base::expected_copy_base; }; #else -template -struct expected_move_base; +template struct expected_move_base; #endif template struct expected_move_base : expected_copy_base { @@ -999,14 +967,16 @@ struct expected_move_base : expected_copy_base { }; // This class manages conditionally having a trivial copy assignment operator -template >::value - &&TL_EXPECTED_IS_TRIVIALLY_COPY_ASSIGNABLE(E)::value - &&TL_EXPECTED_IS_TRIVIALLY_COPY_CONSTRUCTIBLE(E)::value - &&TL_EXPECTED_IS_TRIVIALLY_DESTRUCTIBLE(E)::value> +template < + class T, class E, + bool = + is_void_or< + T, conjunction>::value && + TL_EXPECTED_IS_TRIVIALLY_COPY_ASSIGNABLE(E)::value && + TL_EXPECTED_IS_TRIVIALLY_COPY_CONSTRUCTIBLE(E)::value && + TL_EXPECTED_IS_TRIVIALLY_DESTRUCTIBLE(E)::value> struct expected_copy_assign_base : expected_move_base { using expected_move_base::expected_move_base; }; @@ -1023,8 +993,8 @@ struct expected_copy_assign_base : expected_move_base { this->assign(rhs); return *this; } - expected_copy_assign_base &operator=(expected_copy_assign_base &&rhs) = - default; + expected_copy_assign_base & + operator=(expected_copy_assign_base &&rhs) = default; }; // This class manages conditionally having a trivial move assignment operator @@ -1033,20 +1003,20 @@ struct expected_copy_assign_base : expected_move_base { // to make do with a non-trivial move assignment operator even if T is trivially // move assignable #ifndef TL_EXPECTED_GCC49 -template , - std::is_trivially_move_constructible, - std::is_trivially_move_assignable>>:: - value &&std::is_trivially_destructible::value - &&std::is_trivially_move_constructible::value - &&std::is_trivially_move_assignable::value> +template < + class T, class E, + bool = is_void_or< + T, conjunction, + std::is_trivially_move_constructible, + std::is_trivially_move_assignable>>::value && + std::is_trivially_destructible::value && + std::is_trivially_move_constructible::value && + std::is_trivially_move_assignable::value> struct expected_move_assign_base : expected_copy_assign_base { using expected_copy_assign_base::expected_copy_assign_base; }; #else -template -struct expected_move_assign_base; +template struct expected_move_assign_base; #endif template @@ -1059,13 +1029,13 @@ struct expected_move_assign_base expected_move_assign_base(expected_move_assign_base &&rhs) = default; - expected_move_assign_base &operator=(const expected_move_assign_base &rhs) = - default; + expected_move_assign_base & + operator=(const expected_move_assign_base &rhs) = default; expected_move_assign_base & operator=(expected_move_assign_base &&rhs) noexcept( - std::is_nothrow_move_constructible::value - &&std::is_nothrow_move_assignable::value) { + std::is_nothrow_move_constructible::value && + std::is_nothrow_move_assignable::value) { this->assign(std::move(rhs)); return *this; } @@ -1082,10 +1052,10 @@ struct expected_delete_ctor_base { expected_delete_ctor_base() = default; expected_delete_ctor_base(const expected_delete_ctor_base &) = default; expected_delete_ctor_base(expected_delete_ctor_base &&) noexcept = default; - expected_delete_ctor_base &operator=(const expected_delete_ctor_base &) = - default; - expected_delete_ctor_base &operator=(expected_delete_ctor_base &&) noexcept = - default; + expected_delete_ctor_base & + operator=(const expected_delete_ctor_base &) = default; + expected_delete_ctor_base & + operator=(expected_delete_ctor_base &&) noexcept = default; }; template @@ -1093,10 +1063,10 @@ struct expected_delete_ctor_base { expected_delete_ctor_base() = default; expected_delete_ctor_base(const expected_delete_ctor_base &) = default; expected_delete_ctor_base(expected_delete_ctor_base &&) noexcept = delete; - expected_delete_ctor_base &operator=(const expected_delete_ctor_base &) = - default; - expected_delete_ctor_base &operator=(expected_delete_ctor_base &&) noexcept = - default; + expected_delete_ctor_base & + operator=(const expected_delete_ctor_base &) = default; + expected_delete_ctor_base & + operator=(expected_delete_ctor_base &&) noexcept = default; }; template @@ -1104,10 +1074,10 @@ struct expected_delete_ctor_base { expected_delete_ctor_base() = default; expected_delete_ctor_base(const expected_delete_ctor_base &) = delete; expected_delete_ctor_base(expected_delete_ctor_base &&) noexcept = default; - expected_delete_ctor_base &operator=(const expected_delete_ctor_base &) = - default; - expected_delete_ctor_base &operator=(expected_delete_ctor_base &&) noexcept = - default; + expected_delete_ctor_base & + operator=(const expected_delete_ctor_base &) = default; + expected_delete_ctor_base & + operator=(expected_delete_ctor_base &&) noexcept = default; }; template @@ -1115,10 +1085,10 @@ struct expected_delete_ctor_base { expected_delete_ctor_base() = default; expected_delete_ctor_base(const expected_delete_ctor_base &) = delete; expected_delete_ctor_base(expected_delete_ctor_base &&) noexcept = delete; - expected_delete_ctor_base &operator=(const expected_delete_ctor_base &) = - default; - expected_delete_ctor_base &operator=(expected_delete_ctor_base &&) noexcept = - default; + expected_delete_ctor_base & + operator=(const expected_delete_ctor_base &) = default; + expected_delete_ctor_base & + operator=(expected_delete_ctor_base &&) noexcept = default; }; // expected_delete_assign_base will conditionally delete copy and move @@ -1138,10 +1108,10 @@ struct expected_delete_assign_base { expected_delete_assign_base(const expected_delete_assign_base &) = default; expected_delete_assign_base(expected_delete_assign_base &&) noexcept = default; - expected_delete_assign_base &operator=(const expected_delete_assign_base &) = - default; - expected_delete_assign_base &operator=( - expected_delete_assign_base &&) noexcept = default; + expected_delete_assign_base & + operator=(const expected_delete_assign_base &) = default; + expected_delete_assign_base & + operator=(expected_delete_assign_base &&) noexcept = default; }; template @@ -1150,10 +1120,10 @@ struct expected_delete_assign_base { expected_delete_assign_base(const expected_delete_assign_base &) = default; expected_delete_assign_base(expected_delete_assign_base &&) noexcept = default; - expected_delete_assign_base &operator=(const expected_delete_assign_base &) = - default; - expected_delete_assign_base &operator=( - expected_delete_assign_base &&) noexcept = delete; + expected_delete_assign_base & + operator=(const expected_delete_assign_base &) = default; + expected_delete_assign_base & + operator=(expected_delete_assign_base &&) noexcept = delete; }; template @@ -1162,10 +1132,10 @@ struct expected_delete_assign_base { expected_delete_assign_base(const expected_delete_assign_base &) = default; expected_delete_assign_base(expected_delete_assign_base &&) noexcept = default; - expected_delete_assign_base &operator=(const expected_delete_assign_base &) = - delete; - expected_delete_assign_base &operator=( - expected_delete_assign_base &&) noexcept = default; + expected_delete_assign_base & + operator=(const expected_delete_assign_base &) = delete; + expected_delete_assign_base & + operator=(expected_delete_assign_base &&) noexcept = default; }; template @@ -1174,10 +1144,10 @@ struct expected_delete_assign_base { expected_delete_assign_base(const expected_delete_assign_base &) = default; expected_delete_assign_base(expected_delete_assign_base &&) noexcept = default; - expected_delete_assign_base &operator=(const expected_delete_assign_base &) = - delete; - expected_delete_assign_base &operator=( - expected_delete_assign_base &&) noexcept = delete; + expected_delete_assign_base & + operator=(const expected_delete_assign_base &) = delete; + expected_delete_assign_base & + operator=(expected_delete_assign_base &&) noexcept = delete; }; // This is needed to be able to construct the expected_default_ctor_base which @@ -1198,34 +1168,32 @@ struct expected_default_ctor_base { expected_default_ctor_base const &) noexcept = default; constexpr expected_default_ctor_base(expected_default_ctor_base &&) noexcept = default; - expected_default_ctor_base &operator=( - expected_default_ctor_base const &) noexcept = default; - expected_default_ctor_base &operator=( - expected_default_ctor_base &&) noexcept = default; + expected_default_ctor_base & + operator=(expected_default_ctor_base const &) noexcept = default; + expected_default_ctor_base & + operator=(expected_default_ctor_base &&) noexcept = default; constexpr explicit expected_default_ctor_base(default_constructor_tag) {} }; // This specialization is for when T is not default constructible -template -struct expected_default_ctor_base { +template struct expected_default_ctor_base { constexpr expected_default_ctor_base() noexcept = delete; constexpr expected_default_ctor_base( expected_default_ctor_base const &) noexcept = default; constexpr expected_default_ctor_base(expected_default_ctor_base &&) noexcept = default; - expected_default_ctor_base &operator=( - expected_default_ctor_base const &) noexcept = default; - expected_default_ctor_base &operator=( - expected_default_ctor_base &&) noexcept = default; + expected_default_ctor_base & + operator=(expected_default_ctor_base const &) noexcept = default; + expected_default_ctor_base & + operator=(expected_default_ctor_base &&) noexcept = default; constexpr explicit expected_default_ctor_base(default_constructor_tag) {} }; -} // namespace detail +} // namespace detail -template -class bad_expected_access : public std::exception { - public: +template class bad_expected_access : public std::exception { +public: explicit bad_expected_access(E e) : m_val(std::move(e)) {} virtual const char *what() const noexcept override { @@ -1237,7 +1205,7 @@ class bad_expected_access : public std::exception { const E &&error() const && { return std::move(m_val); } E &&error() && { return std::move(m_val); } - private: +private: E m_val; }; @@ -1286,42 +1254,40 @@ class expected : private detail::expected_move_assign_base, using impl_base = detail::expected_move_assign_base; using ctor_base = detail::expected_default_ctor_base; - public: +public: typedef T value_type; typedef E error_type; typedef unexpected unexpected_type; -#if defined(TL_EXPECTED_CXX14) && !defined(TL_EXPECTED_GCC49) && \ +#if defined(TL_EXPECTED_CXX14) && !defined(TL_EXPECTED_GCC49) && \ !defined(TL_EXPECTED_GCC54) && !defined(TL_EXPECTED_GCC55) - template - TL_EXPECTED_11_CONSTEXPR auto and_then(F &&f) & { + template TL_EXPECTED_11_CONSTEXPR auto and_then(F &&f) & { return and_then_impl(*this, std::forward(f)); } - template - TL_EXPECTED_11_CONSTEXPR auto and_then(F &&f) && { + template TL_EXPECTED_11_CONSTEXPR auto and_then(F &&f) && { return and_then_impl(std::move(*this), std::forward(f)); } - template - constexpr auto and_then(F &&f) const & { + template constexpr auto and_then(F &&f) const & { return and_then_impl(*this, std::forward(f)); } #ifndef TL_EXPECTED_NO_CONSTRR - template - constexpr auto and_then(F &&f) const && { + template constexpr auto and_then(F &&f) const && { return and_then_impl(std::move(*this), std::forward(f)); } #endif #else template - TL_EXPECTED_11_CONSTEXPR auto and_then(F &&f) & -> decltype(and_then_impl( - std::declval(), std::forward(f))) { + TL_EXPECTED_11_CONSTEXPR auto + and_then(F &&f) & -> decltype(and_then_impl(std::declval(), + std::forward(f))) { return and_then_impl(*this, std::forward(f)); } template - TL_EXPECTED_11_CONSTEXPR auto and_then(F &&f) && -> decltype(and_then_impl( - std::declval(), std::forward(f))) { + TL_EXPECTED_11_CONSTEXPR auto + and_then(F &&f) && -> decltype(and_then_impl(std::declval(), + std::forward(f))) { return and_then_impl(std::move(*this), std::forward(f)); } template @@ -1339,22 +1305,18 @@ class expected : private detail::expected_move_assign_base, #endif #endif -#if defined(TL_EXPECTED_CXX14) && !defined(TL_EXPECTED_GCC49) && \ +#if defined(TL_EXPECTED_CXX14) && !defined(TL_EXPECTED_GCC49) && \ !defined(TL_EXPECTED_GCC54) && !defined(TL_EXPECTED_GCC55) - template - TL_EXPECTED_11_CONSTEXPR auto map(F &&f) & { + template TL_EXPECTED_11_CONSTEXPR auto map(F &&f) & { return expected_map_impl(*this, std::forward(f)); } - template - TL_EXPECTED_11_CONSTEXPR auto map(F &&f) && { + template TL_EXPECTED_11_CONSTEXPR auto map(F &&f) && { return expected_map_impl(std::move(*this), std::forward(f)); } - template - constexpr auto map(F &&f) const & { + template constexpr auto map(F &&f) const & { return expected_map_impl(*this, std::forward(f)); } - template - constexpr auto map(F &&f) const && { + template constexpr auto map(F &&f) const && { return expected_map_impl(std::move(*this), std::forward(f)); } #else @@ -1387,22 +1349,18 @@ class expected : private detail::expected_move_assign_base, #endif #endif -#if defined(TL_EXPECTED_CXX14) && !defined(TL_EXPECTED_GCC49) && \ +#if defined(TL_EXPECTED_CXX14) && !defined(TL_EXPECTED_GCC49) && \ !defined(TL_EXPECTED_GCC54) && !defined(TL_EXPECTED_GCC55) - template - TL_EXPECTED_11_CONSTEXPR auto transform(F &&f) & { + template TL_EXPECTED_11_CONSTEXPR auto transform(F &&f) & { return expected_map_impl(*this, std::forward(f)); } - template - TL_EXPECTED_11_CONSTEXPR auto transform(F &&f) && { + template TL_EXPECTED_11_CONSTEXPR auto transform(F &&f) && { return expected_map_impl(std::move(*this), std::forward(f)); } - template - constexpr auto transform(F &&f) const & { + template constexpr auto transform(F &&f) const & { return expected_map_impl(*this, std::forward(f)); } - template - constexpr auto transform(F &&f) const && { + template constexpr auto transform(F &&f) const && { return expected_map_impl(std::move(*this), std::forward(f)); } #else @@ -1435,22 +1393,18 @@ class expected : private detail::expected_move_assign_base, #endif #endif -#if defined(TL_EXPECTED_CXX14) && !defined(TL_EXPECTED_GCC49) && \ +#if defined(TL_EXPECTED_CXX14) && !defined(TL_EXPECTED_GCC49) && \ !defined(TL_EXPECTED_GCC54) && !defined(TL_EXPECTED_GCC55) - template - TL_EXPECTED_11_CONSTEXPR auto map_error(F &&f) & { + template TL_EXPECTED_11_CONSTEXPR auto map_error(F &&f) & { return map_error_impl(*this, std::forward(f)); } - template - TL_EXPECTED_11_CONSTEXPR auto map_error(F &&f) && { + template TL_EXPECTED_11_CONSTEXPR auto map_error(F &&f) && { return map_error_impl(std::move(*this), std::forward(f)); } - template - constexpr auto map_error(F &&f) const & { + template constexpr auto map_error(F &&f) const & { return map_error_impl(*this, std::forward(f)); } - template - constexpr auto map_error(F &&f) const && { + template constexpr auto map_error(F &&f) const && { return map_error_impl(std::move(*this), std::forward(f)); } #else @@ -1482,24 +1436,20 @@ class expected : private detail::expected_move_assign_base, } #endif #endif - template - expected TL_EXPECTED_11_CONSTEXPR or_else(F &&f) & { + template expected TL_EXPECTED_11_CONSTEXPR or_else(F &&f) & { return or_else_impl(*this, std::forward(f)); } - template - expected TL_EXPECTED_11_CONSTEXPR or_else(F &&f) && { + template expected TL_EXPECTED_11_CONSTEXPR or_else(F &&f) && { return or_else_impl(std::move(*this), std::forward(f)); } - template - expected constexpr or_else(F &&f) const & { + template expected constexpr or_else(F &&f) const & { return or_else_impl(*this, std::forward(f)); } #ifndef TL_EXPECTED_NO_CONSTRR - template - expected constexpr or_else(F &&f) const && { + template expected constexpr or_else(F &&f) const && { return or_else_impl(std::move(*this), std::forward(f)); } #endif @@ -1812,7 +1762,7 @@ class expected : private detail::expected_move_assign_base, } } - private: +private: using t_is_void = std::true_type; using t_is_not_void = std::false_type; using t_is_nothrow_move_constructible = std::true_type; @@ -1899,17 +1849,16 @@ class expected : private detail::expected_move_assign_base, #endif } - public: +public: template detail::enable_if_t::value && detail::is_swappable::value && (std::is_nothrow_move_constructible::value || std::is_nothrow_move_constructible::value)> - swap(expected &rhs) noexcept( - std::is_nothrow_move_constructible::value - &&detail::is_nothrow_swappable::value - &&std::is_nothrow_move_constructible::value - &&detail::is_nothrow_swappable::value) { + swap(expected &rhs) noexcept(std::is_nothrow_move_constructible::value && + detail::is_nothrow_swappable::value && + std::is_nothrow_move_constructible::value && + detail::is_nothrow_swappable::value) { if (has_value() && rhs.has_value()) { swap_where_both_have_value(rhs, typename std::is_void::type{}); } else if (!has_value() && rhs.has_value()) { @@ -1983,15 +1932,13 @@ class expected : private detail::expected_move_assign_base, constexpr const E &&error() const && { return std::move(err().value()); } TL_EXPECTED_11_CONSTEXPR E &&error() && { return std::move(err().value()); } - template - constexpr T value_or(U &&v) const & { + template constexpr T value_or(U &&v) const & { static_assert(std::is_copy_constructible::value && std::is_convertible::value, "T must be copy-constructible and convertible to from U&&"); return bool(*this) ? **this : static_cast(std::forward(v)); } - template - TL_EXPECTED_11_CONSTEXPR T value_or(U &&v) && { + template TL_EXPECTED_11_CONSTEXPR T value_or(U &&v) && { static_assert(std::is_move_constructible::value && std::is_convertible::value, "T must be move-constructible and convertible to from U&&"); @@ -2000,12 +1947,9 @@ class expected : private detail::expected_move_assign_base, }; namespace detail { -template -using exp_t = typename detail::decay_t::value_type; -template -using err_t = typename detail::decay_t::error_type; -template -using ret_t = expected>; +template using exp_t = typename detail::decay_t::value_type; +template using err_t = typename detail::decay_t::error_type; +template using ret_t = expected>; #ifdef TL_EXPECTED_CXX14 template (exp).error()); } #else -template -struct TC; +template struct TC; template (), *std::declval())), @@ -2165,7 +2108,7 @@ auto expected_map_impl(Exp &&exp, F &&f) -> expected> { } #endif -#if defined(TL_EXPECTED_CXX14) && !defined(TL_EXPECTED_GCC49) && \ +#if defined(TL_EXPECTED_CXX14) && !defined(TL_EXPECTED_GCC49) && \ !defined(TL_EXPECTED_GCC54) && !defined(TL_EXPECTED_GCC55) template >::value> * = nullptr, @@ -2326,7 +2269,7 @@ detail::decay_t or_else_impl(Exp &&exp, F &&f) { std::forward(exp)); } #endif -} // namespace detail +} // namespace detail template constexpr bool operator==(const expected &lhs, @@ -2387,6 +2330,6 @@ void swap(expected &lhs, expected &rhs) noexcept(noexcept(lhs.swap(rhs))) { lhs.swap(rhs); } -} // namespace tl +} // namespace tl #endif diff --git a/lib/CMakeLists.txt b/lib/CMakeLists.txt index 5990cc1..7458545 100644 --- a/lib/CMakeLists.txt +++ b/lib/CMakeLists.txt @@ -1,10 +1,10 @@ # Set source files fips_begin_module( oculus ) - fips_src( . ) +fips_src( . ) - fips_deps( g3logger ) +fips_deps( g3logger ) - fips_libs( Boost::system ) +fips_libs( Boost::system ) fips_end_module() diff --git a/lib/DataRx.cpp b/lib/DataRx.cpp index 494b45f..8815bae 100644 --- a/lib/DataRx.cpp +++ b/lib/DataRx.cpp @@ -38,16 +38,15 @@ namespace liboculus { namespace asio = boost::asio; -DataRx::DataRx(const IoServiceThread::IoContextPtr& iosrv) - : OculusMessageHandler(), - _socket(*iosrv), - _buffer(std::make_shared()), - _onConnectCallback() {} +DataRx::DataRx(const IoServiceThread::IoContextPtr &iosrv) + : OculusMessageHandler(), _socket(*iosrv), + _buffer(std::make_shared()), _onConnectCallback() {} DataRx::~DataRx() {} -void DataRx::connect(const asio::ip::address& addr) { - if (isConnected()) return; +void DataRx::connect(const asio::ip::address &addr) { + if (isConnected()) + return; uint16_t port = liboculus::DataPort; @@ -58,14 +57,14 @@ void DataRx::connect(const asio::ip::address& addr) { boost::bind(&DataRx::onConnect, this, _1)); } -void DataRx::connect(const std::string& strAddr) { +void DataRx::connect(const std::string &strAddr) { auto addr(boost::asio::ip::address_v4::from_string(strAddr)); // LOG_IF(FATAL,addr.is_unspecified()) << "Couldn't parse IP address" << // ipAddr; connect(addr); } -void DataRx::onConnect(const boost::system::error_code& ec) { +void DataRx::onConnect(const boost::system::error_code &ec) { if (ec) { LOG(WARNING) << "Error on connect: " << ec.message(); _socket.close(); @@ -75,7 +74,8 @@ void DataRx::onConnect(const boost::system::error_code& ec) { LOG(DEBUG) << "Connected to sonar!"; restartReceiveCycle(); - if (_onConnectCallback) _onConnectCallback(); + if (_onConnectCallback) + _onConnectCallback(); } //=== Readers @@ -94,7 +94,8 @@ void DataRx::restartReceiveCycle() { LOG(DEBUG) << "== Restarting DataRx state machine =="; // Before abandoning the current data, post that it's been received - if (_buffer->size() > 0) haveRead(*_buffer); + if (_buffer->size() > 0) + haveRead(*_buffer); if (_buffer.use_count() > 1) { _buffer = std::make_shared(); @@ -107,7 +108,7 @@ void DataRx::restartReceiveCycle() { //==== States in the state machine... ==== -void DataRx::rxFirstByteOculusId(const boost::system::error_code& ec, +void DataRx::rxFirstByteOculusId(const boost::system::error_code &ec, std::size_t bytes_transferred) { if (ec) { LOG(WARNING) << "Error on receive of header: " << ec.message(); @@ -128,7 +129,7 @@ void DataRx::rxFirstByteOculusId(const boost::system::error_code& ec, restartReceiveCycle(); } -void DataRx::rxSecondByteOculusId(const boost::system::error_code& ec, +void DataRx::rxSecondByteOculusId(const boost::system::error_code &ec, std::size_t bytes_transferred) { if (ec) { LOG(WARNING) << "Error on receive of header: " << ec.message(); @@ -151,7 +152,7 @@ void DataRx::rxSecondByteOculusId(const boost::system::error_code& ec, restartReceiveCycle(); } -void DataRx::rxHeader(const boost::system::error_code& ec, +void DataRx::rxHeader(const boost::system::error_code &ec, std::size_t bytes_transferred) { if (ec) { LOG(WARNING) << "Error on receive of header: " << ec.message(); @@ -181,7 +182,7 @@ void DataRx::rxHeader(const boost::system::error_code& ec, readUpTo(packetSize, boost::bind(&DataRx::rxPacket, this, _1, _2)); } -void DataRx::rxPacket(const boost::system::error_code& ec, +void DataRx::rxPacket(const boost::system::error_code &ec, std::size_t bytes_transferred) { MessageHeader hdr(_buffer); @@ -241,4 +242,4 @@ void DataRx::rxPacket(const boost::system::error_code& ec, restartReceiveCycle(); } -} // namespace liboculus +} // namespace liboculus diff --git a/lib/IoServiceThread.cpp b/lib/IoServiceThread.cpp index 9c9ffdf..c01d7bc 100644 --- a/lib/IoServiceThread.cpp +++ b/lib/IoServiceThread.cpp @@ -47,13 +47,15 @@ IoServiceThread::IoServiceThread() IoServiceThread::~IoServiceThread() {} void IoServiceThread::start() { - if (_thread) return; // running + if (_thread) + return; // running _thread.reset( new std::thread(boost::bind(&IoServiceThread::threadExec, this))); } void IoServiceThread::stop() { - if (!_thread) return; + if (!_thread) + return; #if BOOST_VERSION >= 106600 _work_guard.reset(); #endif @@ -61,7 +63,8 @@ void IoServiceThread::stop() { } void IoServiceThread::join() { - if (!_thread) return; + if (!_thread) + return; _thread->join(); _context->reset(); _thread.reset(); @@ -69,4 +72,4 @@ void IoServiceThread::join() { void IoServiceThread::threadExec() { _context->run(); } -} // namespace liboculus +} // namespace liboculus diff --git a/lib/OculusMessageHandler.cpp b/lib/OculusMessageHandler.cpp index a227f0d..090c20c 100644 --- a/lib/OculusMessageHandler.cpp +++ b/lib/OculusMessageHandler.cpp @@ -47,13 +47,15 @@ void OculusMessageHandler::setCallback( template <> void OculusMessageHandler::callback( const SimplePingResultV1 &data) { - if (_simplePingCallback) _simplePingCallback(data); + if (_simplePingCallback) + _simplePingCallback(data); } template <> void OculusMessageHandler::callback( const SimplePingResultV2 &data) { - if (_simplePing2Callback) _simplePing2Callback(data); + if (_simplePing2Callback) + _simplePing2Callback(data); } -}; // namespace liboculus +}; // namespace liboculus diff --git a/lib/SimpleFireMessage.cpp b/lib/SimpleFireMessage.cpp index 0487bce..785d456 100644 --- a/lib/SimpleFireMessage.cpp +++ b/lib/SimpleFireMessage.cpp @@ -37,14 +37,12 @@ namespace liboculus { // Specializations for the cases where the behavior actually varies between // the two SimpleFireMessage types -template <> -float SimpleFireMessage::range() const { +template <> float SimpleFireMessage::range() const { return fireMsg()->range; } -template <> -float SimpleFireMessage::range() const { +template <> float SimpleFireMessage::range() const { return fireMsg()->rangePercent; } -} // namespace liboculus +} // namespace liboculus diff --git a/lib/SonarConfiguration.cpp b/lib/SonarConfiguration.cpp index ceffa8e..8d1e7b2 100644 --- a/lib/SonarConfiguration.cpp +++ b/lib/SonarConfiguration.cpp @@ -40,19 +40,15 @@ namespace liboculus { SonarConfiguration::SonarConfiguration() - : _sendRangeAsMeters(true), - _rangeInMeters(5), - _sendGain(true), - _simpleReturn(true), - _gainAssistance(true), - _512beams(true), + : _sendRangeAsMeters(true), _rangeInMeters(5), _sendGain(true), + _simpleReturn(true), _gainAssistance(true), _512beams(true), _dataSize(dataSize8Bit) { memset(&_sfm, 0, sizeof(ConfigFireMessage)); // Fill in OculusMessageHeader _sfm.head - _sfm.head.oculusId = OCULUS_CHECK_ID; // 0x4f53 + _sfm.head.oculusId = OCULUS_CHECK_ID; // 0x4f53 _sfm.head.srcDeviceId = 0; - _sfm.head.dstDeviceId = 0; // n.b. ignored by device + _sfm.head.dstDeviceId = 0; // n.b. ignored by device _sfm.head.msgId = messageSimpleFire; _sfm.head.msgVersion = 2; _sfm.head.payloadSize = @@ -60,15 +56,15 @@ SonarConfiguration::SonarConfiguration() _sfm.masterMode = OCULUS_HIGH_FREQ; _sfm.pingRate = pingRateNormal; - _sfm.networkSpeed = 0xff; // uint8_t; can reduce network speed for bad links - _sfm.gammaCorrection = 127; // uint8_t; for 127, gamma = 0.5 + _sfm.networkSpeed = 0xff; // uint8_t; can reduce network speed for bad links + _sfm.gammaCorrection = 127; // uint8_t; for 127, gamma = 0.5 - updateFlags(); // Set to defaults + updateFlags(); // Set to defaults - _sfm.rangePercent = 2; // 2 m; can be percent or meters, flag controlled + _sfm.rangePercent = 2; // 2 m; can be percent or meters, flag controlled _sfm.gainPercent = 50; - _sfm.speedOfSound = 0.0; // m/s 0 to calculate SoS from salinity - _sfm.salinity = 0.0; // ppt; 0 for freshwater, 35 for seawater + _sfm.speedOfSound = 0.0; // m/s 0 to calculate SoS from salinity + _sfm.salinity = 0.0; // ppt; 0 for freshwater, 35 for seawater } SonarConfiguration &SonarConfiguration::setRange(double input) { @@ -143,8 +139,8 @@ SonarConfiguration &SonarConfiguration::set512Beams(bool v) { //== Serialization functions template <> -std::vector SonarConfiguration::serialize() - const { +std::vector +SonarConfiguration::serialize() const { updateFlags(); // Corner case. If in 32bit mode, range is always a percentage of max range @@ -168,8 +164,8 @@ std::vector SonarConfiguration::serialize() } template <> -std::vector SonarConfiguration::serialize() - const { +std::vector +SonarConfiguration::serialize() const { updateFlags(); // As of right now, since OculusSimpleFireMessage and OculusSimpleFireMessage2 @@ -223,4 +219,4 @@ void SonarConfiguration::dump() const { << "\n use 512 beams " << get512Beams(); } -} // namespace liboculus +} // namespace liboculus diff --git a/lib/SonarPlayer.cpp b/lib/SonarPlayer.cpp index b0ad133..29d3c5b 100644 --- a/lib/SonarPlayer.cpp +++ b/lib/SonarPlayer.cpp @@ -49,11 +49,12 @@ using liboculus::MessageHeader; using liboculus::SimplePingResult; /// Static function which automatically detects file type -shared_ptr SonarPlayerBase::OpenFile( - const std::string &filename) { +shared_ptr +SonarPlayerBase::OpenFile(const std::string &filename) { std::ifstream f(filename); - if (!f.is_open()) return nullptr; + if (!f.is_open()) + return nullptr; char c; f.get(c); @@ -105,7 +106,8 @@ bool RawSonarPlayer::nextPing() { _input.get(reinterpret_cast(buffer->data()), sizeof(MessageHeader)); MessageHeader header(buffer); - if (!header.valid()) return false; + if (!header.valid()) + return false; // Read the rest of the data buffer->resize(header.packetSize()); @@ -123,4 +125,4 @@ bool RawSonarPlayer::nextPing() { return true; } -} // namespace liboculus +} // namespace liboculus diff --git a/lib/SonarStatus.cpp b/lib/SonarStatus.cpp index 22d5f65..5851f41 100644 --- a/lib/SonarStatus.cpp +++ b/lib/SonarStatus.cpp @@ -73,4 +73,4 @@ void SonarStatus::dump() const { << msg()->versionInfo.firmwareDate2; } -} // namespace liboculus +} // namespace liboculus diff --git a/lib/StatusRx.cpp b/lib/StatusRx.cpp index cef0bf0..fbe271a 100644 --- a/lib/StatusRx.cpp +++ b/lib/StatusRx.cpp @@ -49,10 +49,7 @@ using std::string; // StatusRx - a listening socket for oculus status messages StatusRx::StatusRx(const IoServiceThread::IoContextPtr &iosrv) - : _num_valid_rx(0), - _num_invalid_rx(0), - _socket(*iosrv), - _deadline(*iosrv), + : _num_valid_rx(0), _num_invalid_rx(0), _socket(*iosrv), _deadline(*iosrv), _sonarStatusCallback([](const SonarStatus &, bool) {}) { doConnect(); } @@ -185,4 +182,4 @@ bool StatusRx::parseStatus(const SonarStatus &status) { return true; } -} // namespace liboculus +} // namespace liboculus diff --git a/liboculus.repos b/liboculus.repos new file mode 100644 index 0000000..5e9bf27 --- /dev/null +++ b/liboculus.repos @@ -0,0 +1,5 @@ +repositories: + g3log_ros: + type: git + url: https://gitlab.com/apl-ocean-engineering/g3log_ros.git + version: main diff --git a/liboculus.rosinstall b/liboculus.rosinstall deleted file mode 100644 index 3573810..0000000 --- a/liboculus.rosinstall +++ /dev/null @@ -1 +0,0 @@ -- git: {local-name: g3log_ros, uri: "https://gitlab.com/apl-ocean-engineering/g3log_ros.git", version: main} diff --git a/package.xml b/package.xml index 70b6c7d..2970fb2 100644 --- a/package.xml +++ b/package.xml @@ -1,15 +1,26 @@ - + liboculus 0.0.1 A ROS version of the Oculus sonar codebase - igor + Aaron Marburg + Aaron Marburg BSD - catkin + catkin + ament_cmake g3log_ros + boost + + boost + + + catkin + ament_cmake + + diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 18d7383..f000a25 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -1,6 +1,4 @@ - add_definitions(-DTEST_DATA_PATH="${CMAKE_CURRENT_SOURCE_DIR}/data") fips_include_directories( ${CMAKE_CURRENT_SOURCE_DIR}/data ) - -add_subdirectory( unit/ ) +add_subdirectory(unit/) diff --git a/test/data/test_data.h b/test/data/test_data.h index df92b19..eb3dd59 100644 --- a/test/data/test_data.h +++ b/test/data/test_data.h @@ -27,7 +27,8 @@ using std::vector; inline std::shared_ptr Load(const std::string &filename) { std::ifstream inf(filename); - if (!inf.is_open()) return std::make_shared(); + if (!inf.is_open()) + return std::make_shared(); // This feels a little ... wrong inf.seekg(0, std::ios::end); @@ -41,4 +42,4 @@ inline std::shared_ptr Load(const std::string &filename) { return std::make_shared(out.begin(), out.end()); } -} // namespace Oculus_TestData +} // namespace Oculus_TestData diff --git a/test/unit/CMakeLists.txt b/test/unit/CMakeLists.txt old mode 100755 new mode 100644 index af50833..948c6cc --- a/test/unit/CMakeLists.txt +++ b/test/unit/CMakeLists.txt @@ -1,8 +1,6 @@ - - ## NO_TEMPLATE == we provide main() ## Our main initializes g3log gtest_begin( oculus NO_TEMPLATE ) - fips_src( . ) - fips_deps( oculus ) +fips_src( . ) +fips_deps( oculus ) gtest_end() diff --git a/test/unit/test_SonarConfiguration.cpp b/test/unit/test_SonarConfiguration.cpp index a564bea..b87a4c5 100644 --- a/test/unit/test_SonarConfiguration.cpp +++ b/test/unit/test_SonarConfiguration.cpp @@ -5,7 +5,7 @@ using namespace liboculus; void validateOculusHeader(const OculusMessageHeader &head) { - ASSERT_EQ(head.oculusId, OCULUS_CHECK_ID); // 0x4f53 + ASSERT_EQ(head.oculusId, OCULUS_CHECK_ID); // 0x4f53 // \TODO exapand validity testing } diff --git a/thirdparty/Oculus/Oculus.h b/thirdparty/Oculus/Oculus.h index 96e8ef9..b8e5f32 100644 --- a/thirdparty/Oculus/Oculus.h +++ b/thirdparty/Oculus/Oculus.h @@ -73,12 +73,12 @@ enum OculusMessageType : uint16_t { }; enum PingRateType : uint8_t { - pingRateNormal = 0x00, // 10Hz max ping rate - pingRateHigh = 0x01, // 15Hz max ping rate - pingRateHighest = 0x02, // 40Hz max ping rate - pingRateLow = 0x03, // 5Hz max ping rate - pingRateLowest = 0x04, // 2Hz max ping rate - pingRateStandby = 0x05, // Disable ping + pingRateNormal = 0x00, // 10Hz max ping rate + pingRateHigh = 0x01, // 15Hz max ping rate + pingRateHighest = 0x02, // 40Hz max ping rate + pingRateLow = 0x03, // 5Hz max ping rate + pingRateLowest = 0x04, // 2Hz max ping rate + pingRateStandby = 0x05, // Disable ping }; // ----------------------------------------------------------------------------- @@ -119,41 +119,40 @@ enum OculusPartNumberType : uint16_t { partNumberEnd = 0xFFFF }; struct OculusMessageHeader { - public: - uint16_t oculusId; // Fixed ID 0x4f53 - uint16_t srcDeviceId; // The device id of the source - uint16_t dstDeviceId; // The device id of the destination - uint16_t msgId; // Message identifier +public: + uint16_t oculusId; // Fixed ID 0x4f53 + uint16_t srcDeviceId; // The device id of the source + uint16_t dstDeviceId; // The device id of the destination + uint16_t msgId; // Message identifier uint16_t msgVersion; - uint32_t - payloadSize; // The size of the message payload (header not included) + uint32_t payloadSize; // The size of the message payload (header not included) uint16_t spare2; }; // ----------------------------------------------------------------------------- typedef struct { - public: - OculusMessageHeader head; // The standard message header +public: + OculusMessageHeader head; // The standard message header uint8_t - masterMode; // mode 0 is flexi mode, needs full fire message (not - // available for third party developers) mode 1 - Low - // Frequency Mode (wide aperture, navigation) mode 2 - High - // Frequency Mode (narrow aperture, target identification) - PingRateType pingRate; // Sets the maximum ping rate. - uint8_t networkSpeed; // Used to reduce the network comms speed (useful for - // high latency shared links) - uint8_t gammaCorrection; // 0 and 0xff = gamma correction = 1.0 - // Set to 127 for gamma correction = 0.5 - uint8_t flags; // bit 0: 0 = interpret range as percent, 1 = interpret range - // as meters bit 1: 0 = 8 bit data, 1 = 16 bit data bit 2: 0 = - // wont send gain, 1 = send gain bit 3: 0 = send full return - // message, 1 = send simple return message - double range; // The range demand in percent or m depending on flags - double gainPercent; // The gain demand - double speedOfSound; // ms-1, if set to zero then internal calc will apply - // using salinity - double salinity; // ppt, set to zero if we are in fresh water + masterMode; // mode 0 is flexi mode, needs full fire message (not + // available for third party developers) mode 1 - Low + // Frequency Mode (wide aperture, navigation) mode 2 - High + // Frequency Mode (narrow aperture, target identification) + PingRateType pingRate; // Sets the maximum ping rate. + uint8_t networkSpeed; // Used to reduce the network comms speed (useful for + // high latency shared links) + uint8_t gammaCorrection; // 0 and 0xff = gamma correction = 1.0 + // Set to 127 for gamma correction = 0.5 + uint8_t flags; // bit 0: 0 = interpret range as percent, 1 = interpret range + // as meters bit 1: 0 = 8 bit data, 1 = 16 bit data bit 2: 0 = + // wont send gain, 1 = send gain bit 3: 0 = send full return + // message, 1 = send simple return message + double range; // The range demand in percent or m depending on flags + double gainPercent; // The gain demand + double speedOfSound; // ms-1, if set to zero then internal calc will apply + // using salinity + double salinity; // ppt, set to zero if we are in fresh water } OculusSimpleFireMessage; typedef struct { @@ -179,7 +178,7 @@ typedef struct { // ----------------------------------------------------------------------------- typedef struct { - public: +public: typedef OculusSimpleFireMessage FireMsg_t; OculusSimpleFireMessage fireMessage; @@ -208,7 +207,7 @@ typedef struct { } OculusSimplePingResult; typedef struct { - public: +public: typedef OculusSimpleFireMessage2 FireMsg_t; OculusSimpleFireMessage2 fireMessage; @@ -242,7 +241,7 @@ typedef struct { // ----------------------------------------------------------------------------- struct OculusVersionInfo { - public: +public: uint32_t firmwareVersion0; /* The arm0 firmware version major(8 bits), minor(8 bits), build (16 bits) */ uint32_t firmwareDate0; /* The arm0 firmware date */ @@ -255,7 +254,7 @@ struct OculusVersionInfo { // ----------------------------------------------------------------------------- struct OculusStatusMsg { - public: +public: OculusMessageHeader hdr; uint32_t deviceId; @@ -472,12 +471,12 @@ typedef struct { uint8_t b0; uint8_t b1; uint8_t b2; - uint32_t imageOffset; // The offset in bytes of the image data (CHN, CQI, BQI - // or BMG) from the start of the buffer + uint32_t imageOffset; // The offset in bytes of the image data (CHN, CQI, BQI + // or BMG) from the start of the buffer uint32_t - imageSize; // The size in bytes of the image data (CHN, CQI, BQI or BMG) - uint32_t messageSize; // The total size in bytes of the network message - // *** NOT ADDITIONAL VARIABLES BEYOND THIS POINT *** + imageSize; // The size in bytes of the image data (CHN, CQI, BQI or BMG) + uint32_t messageSize; // The total size in bytes of the network message + // *** NOT ADDITIONAL VARIABLES BEYOND THIS POINT *** // There will be an array of bearings (shorts) found at the end of the message // structure Allocated at run time short bearings[]; The bearings to each of // the beams in 0.01 degree resolution @@ -517,7 +516,7 @@ struct OculusInfo { // Maximum high-frequency range double maxHF; // Description - char* model; + char *model; }; #pragma pack(pop) diff --git a/tools/CMakeLists.txt b/tools/CMakeLists.txt index b10ac1c..9a97f1a 100644 --- a/tools/CMakeLists.txt +++ b/tools/CMakeLists.txt @@ -1,12 +1,12 @@ fips_begin_app( oc_client cmdline ) - fips_files( +fips_files( oculus_client.cpp - ) +) - fips_deps( oculus ) +fips_deps( oculus ) - fips_include_directories( +fips_include_directories( ${CMAKE_CURRENT_SOURCE_DIR} - ) +) fips_end_app() diff --git a/tools/oculus_client.cpp b/tools/oculus_client.cpp index 6c24d9a..88390ae 100644 --- a/tools/oculus_client.cpp +++ b/tools/oculus_client.cpp @@ -39,7 +39,8 @@ bool doStop = false; // Catch signals void signalHandler(int signo) { - if (_io_thread) _io_thread->stop(); + if (_io_thread) + _io_thread->stop(); doStop = true; } @@ -178,7 +179,8 @@ int main(int argc, char **argv) { << mean_image_intensity(ping.image()); count++; - if ((stopAfter > 0) && (count >= stopAfter)) _io_thread->stop(); + if ((stopAfter > 0) && (count >= stopAfter)) + _io_thread->stop(); }); // Callback for a SimplePingResultV2 @@ -206,7 +208,8 @@ int main(int argc, char **argv) { << mean_image_intensity(ping.image()); count++; - if ((stopAfter > 0) && (count >= stopAfter)) doStop = true; + if ((stopAfter > 0) && (count >= stopAfter)) + doStop = true; }); // When the _data_rx connects, send the configuration @@ -220,7 +223,8 @@ int main(int argc, char **argv) { // To autoconnect, define a callback for the _status_rx which // connects _data_rx to the received IP address _status_rx.setCallback([&](const SonarStatus &status, bool is_valid) { - if (!is_valid || _data_rx.isConnected()) return; + if (!is_valid || _data_rx.isConnected()) + return; _data_rx.connect(status.ipAddr()); }); } else { @@ -243,7 +247,8 @@ int main(int argc, char **argv) { _io_thread->stop(); _io_thread->join(); - if (output.is_open()) output.close(); + if (output.is_open()) + output.close(); LOG(INFO) << "At exit";