├── .gitignore ├── CMakeLists.txt ├── LICENSE ├── LICENSE.md ├── README.md ├── bindings ├── matlab │ ├── CMakeLists.txt │ ├── clipperplus_clique_mex.cpp │ ├── clique_corenumber_mex.cpp │ ├── clique_optimization_mex.cpp │ ├── mexutils.h │ └── pmc_heuristic_mex.cpp └── python │ ├── CMakeLists.txt │ ├── py_clipperplus.cpp │ ├── setup.py.in │ └── wrapper.h ├── cmake └── pmcConfig.cmake ├── examples ├── README.md ├── data │ └── place_datasets_here.txt ├── demo_clipperp.m ├── demo_pointcloud_regist.m ├── helpers │ ├── affinity_matrix.m │ └── arun.m └── python │ ├── demo_clipperp.py │ └── demo_pointcloud_register.py ├── include └── clipperplus │ ├── clipperplus_clique.h │ ├── clipperplus_graph.h │ ├── clipperplus_heuristic.h │ ├── clique_optimization.h │ ├── debug.h │ └── utils.h ├── src ├── clipperplus_clique.cpp ├── clipperplus_graph.cpp ├── clipperplus_heuristic.cpp ├── clique_optimization.cpp └── utils.cpp └── test ├── CMakeLists.txt ├── clipperplus_test.cpp ├── data └── bun10k.ply ├── main.cpp ├── matlab ├── DIMACS9.mat ├── test_clique.m └── test_dimacs.m └── python └── ex0_test.ipynb /.gitignore: -------------------------------------------------------------------------------- 1 | build/ 2 | .vscode/ 3 | clipper-main/ 4 | pmc-master/ 5 | examples/data/7-Scenes 6 | examples/data/ETH 7 | examples/data/Sun3D 8 | *.asv -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.10) 2 | project(clipperplus VERSION 1.0.0) 3 | 4 | set(CMAKE_CXX_STANDARD 14) 5 | set(CMAKE_CXX_STANDARD_REQUIRED ON) 6 | if(NOT CMAKE_BUILD_TYPE) 7 | message(STATUS "No build type selected, default to Release") 8 | set(CMAKE_BUILD_TYPE "Release" CACHE STRING "Choose build type." FORCE) 9 | endif() 10 | 11 | set(CMAKE_EXPORT_COMPILE_COMMANDS ON) 12 | 13 | ############################################################################### 14 | # Options 15 | ############################################################################### 16 | 17 | option(DEBUG_FLAG "Enable debugging output" OFF) 18 | option(DEBUG_TIMING_FLAG "Enable timing report" OFF) 19 | option(DEBUG_OPTIM_FLAG "Enable debugging clipper optimization" OFF) 20 | 21 | option(BUILD_PMC_HEU "Build PMC heuristic" OFF) 22 | option(BUILD_BINDINGS_MATLAB "Build MATLAB bindings" OFF) 23 | option(BUILD_BINDINGS_PYTHON "Build Python bindings" OFF) 24 | option(BUILD_TESTS "Build testsuite" ON) 25 | 26 | 27 | ############################################################################### 28 | # Dependencies 29 | ############################################################################### 30 | 31 | include(FetchContent) 32 | 33 | find_package(Eigen3 REQUIRED) 34 | message(STATUS "Eigen Version: ${EIGEN3_VERSION_STRING} ${EIGEN3_VERSION}") 35 | 36 | find_package(OpenMP REQUIRED) 37 | 38 | if(BUILD_TESTS) 39 | FetchContent_Declare( 40 | googletest 41 | URL https://github.com/google/googletest/archive/e4fdb87e76b9fc4b01c54ad81aea19d6e994b994.zip 42 | ) 43 | endif() 44 | 45 | if(BUILD_BINDINGS_PYTHON) 46 | FetchContent_Declare(pybind11 47 | GIT_REPOSITORY https://github.com/pybind/pybind11 48 | GIT_TAG v2.9.2 49 | ) 50 | FetchContent_MakeAvailable(pybind11) 51 | endif() 52 | 53 | # For Windows: Prevent overriding the parent project's compiler/linker settings 54 | set(gtest_force_shared_crt ON CACHE BOOL "" FORCE) 55 | FetchContent_MakeAvailable(googletest) 56 | 57 | 58 | ############################################################################### 59 | # Targets 60 | ############################################################################### 61 | 62 | set(CLLIPPER_PLUS_SOURCE_FILES 63 | ${CMAKE_CURRENT_SOURCE_DIR}/src/clipperplus_clique.cpp 64 | ${CMAKE_CURRENT_SOURCE_DIR}/src/clipperplus_graph.cpp 65 | ${CMAKE_CURRENT_SOURCE_DIR}/src/clique_optimization.cpp 66 | ${CMAKE_CURRENT_SOURCE_DIR}/src/clipperplus_heuristic.cpp 67 | ${CMAKE_CURRENT_SOURCE_DIR}/src/utils.cpp 68 | ) 69 | 70 | # source files 71 | add_library(clipperplus SHARED) 72 | target_sources(clipperplus PRIVATE ${CLLIPPER_PLUS_SOURCE_FILES}) 73 | 74 | # headers: 75 | target_include_directories(clipperplus PUBLIC 76 | $ 77 | $) 78 | 79 | # link libraries: 80 | target_link_libraries(clipperplus PUBLIC Eigen3::Eigen) 81 | target_link_libraries(clipperplus PUBLIC OpenMP::OpenMP_CXX) 82 | 83 | 84 | 85 | # debug flag 86 | if(DEBUG_FLAG) 87 | message(STATUS "Enabling debug flag") 88 | target_compile_definitions(clipperplus PRIVATE DEBUG) 89 | endif() 90 | if(DEBUG_OPTIM_FLAG) 91 | message(STATUS "Enabling debug optimization flag") 92 | target_compile_definitions(clipperplus PRIVATE DEBUG_OPTIM) 93 | endif() 94 | if(DEBUG_TIMING_FLAG) 95 | message(STATUS "Enabling debug timing flag") 96 | target_compile_definitions(clipperplus PRIVATE DEBUG_TIMING) 97 | endif() 98 | 99 | # version 100 | set_target_properties(clipperplus PROPERTIES 101 | VERSION ${PROJECT_VERSION}) 102 | target_compile_definitions(clipperplus PUBLIC CLIPPERPLUS_VERSION="${PROJECT_VERSION}") 103 | 104 | 105 | ############################################################################### 106 | # Extras 107 | ############################################################################### 108 | if(BUILD_BINDINGS_MATLAB) 109 | message(STATUS "Attempting to build MATLAB bindings.") 110 | add_subdirectory(bindings/matlab) 111 | endif() 112 | 113 | if(BUILD_BINDINGS_PYTHON) 114 | message(STATUS "Building Python bindings.") 115 | add_subdirectory(bindings/python) 116 | endif() 117 | 118 | 119 | if(BUILD_TESTS) 120 | enable_testing() 121 | add_subdirectory(test) 122 | endif() 123 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | MIT License 2 | 3 | Copyright (c) 2023 ARIA Robotics Laboratory 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 21 | SOFTWARE. 22 | -------------------------------------------------------------------------------- /LICENSE.md: -------------------------------------------------------------------------------- 1 | License 2 | 3 | MIT License 4 | 5 | Copyright (c) 2023 ARIA Robotics Laboratory 6 | 7 | Permission is hereby granted, free of charge, to any person obtaining a copy 8 | of this software and associated documentation files (the "Software"), to deal 9 | in the Software without restriction, including without limitation the rights 10 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 11 | copies of the Software, and to permit persons to whom the Software is 12 | furnished to do so, subject to the following conditions: 13 | 14 | The above copyright notice and this permission notice shall be included in all 15 | copies or substantial portions of the Software. 16 | 17 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 18 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 19 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 20 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 21 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 22 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 23 | SOFTWARE. 24 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # CLIPPER+: A Fast Maximal Clique Algorithm for Robust Global Registration 2 | 3 | CLIPPER+ is an algorithm for finding maximal cliques in unweighted graphs for outlier-robust global registration. The registration problem can be 4 | formulated as a graph and solved by finding its maximum clique. This formulation leads to extreme robustness to outliers; however, finding the 5 | [maximum clique](https://en.wikipedia.org/wiki/Clique_problem) is an NP-hard problem, and therefore approximation is required in practice for large-size problems. 6 | 7 | The performance of an approximation algorithm is evaluated by its computational complexity (the lower the runtime, the 8 | better) and solution accuracy (how close the solution is to the maximum clique). Accordingly, the main contribution of 9 | CLIPPER+ is outperforming the state-of-the-art in accuracy while maintaining a relatively low runtime. CLIPPER+ builds 10 | on prior work (PMC [[2]](#2) and CLIPPER [[3]](#3)) and prunes the graph by removing vertices that have a small core number and cannot be a part of the maximum clique. This will result in a smaller graph, on which the maximum clique can be estimated considerably faster. 11 | 12 | Note 13 | --------- 14 | We are actively optimizing the code and adding new features to this repo. 15 | 16 | 17 | Citation 18 | --------- 19 | If you find this code useful in your research, we ask that you cite: 20 | 21 | - K. Fathian, T. Summers. "CLIPPER+: A Fast Maximal Clique Algorithm for Robust Global Registration," in IEEE Robotics and Automation Letters, 2024. ([Paper](https://arxiv.org/pdf/2402.15464.pdf)) 22 | 23 | ```bibtex 24 | @inproceedings{fathian2024clipper+, 25 | title={CLIPPER+: A Fast Maximal Clique Algorithm for Robust Global Registration}, 26 | author={Fathian, Kaveh and Summers, Tyler}, 27 | journal={IEEE Robotics and Automation Letters}, 28 | year={2024}, 29 | publisher={IEEE} 30 | } 31 | ``` 32 | 33 | Installation 34 | --------- 35 | ### Compilation 36 | 37 | Ensure that cmake is installed on your system. 38 | Upon cloning the repository, run the following commands: 39 | 40 | ```bash 41 | $ mkdir build 42 | $ cd ./build 43 | $ cmake .. 44 | $ make 45 | ``` 46 | 47 | If succesful, tests can be run with the command `./test/tests` 48 | 49 | ### Build Configurations 50 | 51 | The following cmake options are available when building CLIPPER+ : 52 | 53 | | Option | Description K. Fathian, T. Summers, "CLIPPER+: A Graph-Theoretic Framework for Robust Data Association," in *Proc. IEEE Int. Conf. on Robotics and Automation (ICRA)*, 2021, pp. 13828-13834. DOI: 10.1109/ICRA48506.2021.9561069. ([Paper](https://arxiv.org/pdf/2011.10202.pdf)) ([Video](https://youtu.be/QYLHueMhShY)) ([Repository](https://github.com/mit-acl/clipper)) 54 | ndings](#python-bindings) for CLIPPER+. | `OFF` | 55 | | `BUILD_BINDINGS_MATLAB` | Creates [MATLAB bindings](#matlab-bindings) for CLIPPER+. | `OFF` | 56 | | `DEBUG_FLAG` | Enables debugging output | `OFF` | 57 | | `DEBUG_TIMING_FLAG` | Enables timing report | `OFF` | 58 | | `DEBUG_OPTIM_FLAG ` | Enable debugging clipper optimization | `OFF` | 59 | | `DEBUG_BUILD_PMC_HEU` | Builds PMC heuristic | `OFF` | 60 | | `BUILD_TESTS` | Builds Google testsuites | `ON` | 61 | 62 | You can customize these preferences by employing the -D flag during the cmake execution for each individual flag. For instance, you can use the command `cmake -D BUILD_BINDINGS_PYTHON=ON -D DEBUG_FLAG=ON` to enable Python bindings and enable basic debugging output. 63 | 64 | ### Python Bindings 65 | 66 | If Python bindings are built using the `BUILD_BINDINGS_PYTHON` flag (See [Build Configurations](#build-configurations) above), then the generated clipper Python module will need to be installed before it can be imported in any Python 3 program. This can be done by running make: 67 | 68 | ```bash 69 | $ cd ./build 70 | $ make pip-install 71 | ``` 72 | 73 | Or, if the user wishes to install the module using pip directly: 74 | ```bash 75 | $ python3 -m pip install build/bindings/python 76 | ``` 77 | A Jupyter Notebook containing a python example can be found in the [`test/python`](test/python) folder 78 | ### MATLAB Bindings 79 | 80 | If MATLAB is installed on your computer and MATLAB bindings are requested using the cmake flag `BUILD_BINDINGS_MATLAB=ON` (See [Build Configurations](#build-configurations) above), then cmake will create a bindings/matlab folders with additional directives. By running these commands inside your build folder: 81 | ```bashs 82 | $ cd ./bindings/matlab 83 | $ make 84 | ``` 85 | cmake will attempt to find your MATLAB installation and subsequently generate a set of MEX files so that CLIPPER+ can be used from your MATLAB program. 86 | 87 | MATLAB test suites can be found in the [`test/matlab`](test/matlab) folder. For future projects, ensure that all the generated MEX files are located in your current MATLAB path. 88 | 89 | ### Including as a shared library 90 | 91 | A simple way to include `clipperplus` as a shared library in another C++ project is via `cmake`. This method will automatically clone and build `clipperplus`, making the resulting library accessible in your main project. In your project's `CMakeLists.txt` you can add 92 | 93 | ```cmake 94 | set(CLIPPERPLUS_DIR "${CMAKE_CURRENT_BINARY_DIR}/clipperplus-download" CACHE INTERNAL "CLIPPERPLUS build dir" FORCE) 95 | set(DEBUG_FLAG OFF CACHE BOOL "") 96 | set(DEBUG_TIMING_FLAG OFF CACHE BOOL "") 97 | set(DEBUG_OPTIM_FLAG OFF CACHE BOOL "") 98 | set(BUILD_PMC_HEU OFF CACHE BOOL "") 99 | set(BUILD_BINDINGS_MATLAB OFF CACHE BOOL "") 100 | set(BUILD_BINDINGS_PYTHON OFF CACHE BOOL "") 101 | set(BUILD_TESTS OFF CACHE BOOL "") 102 | configure_file(cmake/clipperplus.cmake.in ${CLIPPERPLUS_DIR}/CMakeLists.txt IMMEDIATE @ONLY) 103 | execute_process(COMMAND "${CMAKE_COMMAND}" -G "${CMAKE_GENERATOR}" . WORKING_DIRECTORY ${CLIPPERPLUS_DIR}) 104 | execute_process(COMMAND "${CMAKE_COMMAND}" --build . WORKING_DIRECTORY ${CLIPPERPLUS_DIR}) 105 | add_subdirectory(${CLIPPERPLUS_DIR}/src ${CLIPPERPLUS_DIR}/build) 106 | ``` 107 | 108 | where `cmake/clipperplus.cmake.in` looks like 109 | 110 | ```cmake 111 | 112 | cmake_minimum_required(VERSION 3.10) 113 | project(clipperplus-download NONE) 114 | 115 | include(ExternalProject) 116 | ExternalProject_Add(clipperplus 117 | GIT_REPOSITORY "https://github.com/ariarobotics/clipperp" 118 | GIT_TAG main 119 | SOURCE_DIR "${CMAKE_CURRENT_BINARY_DIR}/src" 120 | BINARY_DIR "${CMAKE_CURRENT_BINARY_DIR}/build" 121 | CONFIGURE_COMMAND "" 122 | BUILD_COMMAND "" 123 | INSTALL_COMMAND "" 124 | TEST_COMMAND "" 125 | ) 126 | ``` 127 | 128 | Then, you can link your project with `clipperplus` using the syntax `target_link_libraries(yourproject clipperplus)`. 129 | 130 | 131 | ## Examples 132 | 133 | See the [`examples`](examples) folder to see demos of CLIPPER+ being used for finding maximal cliques and pointcloud registration. 134 | 135 | 136 | ## Citations 137 | 138 | [1] K. Fathian, T. Summers. "CLIPPER+: A Fast Maximal Clique Algorithm for Robust Global Registration," in *IEEE Robotics and Automation Letters (RAL)*, 2024. ([Paper](https://arxiv.org/pdf/2402.15464.pdf)) 139 | 140 | [2] R. A. Rossi, D. F. Gleich, A. H. Gebremedhin, M. M. Patwary, "A Fast Parallel Maximum Clique Algorithm for Large Sparse Graphs and Temporal Strong Components," *arXiv preprint arXiv:1302.6256*, 2013. ([Repository](https://github.com/ryanrossi/pmc)) 141 | 142 | [3] P. C. Lusk, K. Fathian, J. P. How, "CLIPPER: A Graph-Theoretic Framework for Robust Data Association," in *Proc. IEEE Int. Conf. on Robotics and Automation (ICRA)*, 2021, pp. 13828-13834. DOI: 10.1109/ICRA48506.2021.9561069. ([Paper](https://arxiv.org/pdf/2011.10202.pdf)) ([Video](https://youtu.be/QYLHueMhShY)) ([Repository](https://github.com/mit-acl/clipper)) 143 | 144 | Copyright 2024, Kaveh Fathian. All rights reserved. 145 | 146 | -------------------------------------------------------------------------------- /bindings/matlab/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | find_package(Matlab COMPONENTS MX_LIBRARY) 2 | 3 | if(Matlab_FOUND) 4 | message(STATUS "MATLAB root directory found: ${Matlab_ROOT_DIR}") 5 | 6 | matlab_add_mex(NAME clipperplus_clique_mex SRC clipperplus_clique_mex.cpp LINK_TO Eigen3::Eigen clipperplus) 7 | set_target_properties(clipperplus_clique_mex PROPERTIES COMPILE_FLAGS "-fvisibility=default") 8 | set_target_properties(clipperplus_clique_mex PROPERTIES OUTPUT_NAME clipperplus_clique_mex) 9 | 10 | matlab_add_mex(NAME clique_optimization_mex SRC clique_optimization_mex.cpp LINK_TO Eigen3::Eigen clipperplus) 11 | set_target_properties(clique_optimization_mex PROPERTIES COMPILE_FLAGS "-fvisibility=default") 12 | set_target_properties(clique_optimization_mex PROPERTIES OUTPUT_NAME clique_optimization_mex) 13 | 14 | matlab_add_mex(NAME clique_corenumber_mex SRC clique_corenumber_mex.cpp LINK_TO Eigen3::Eigen clipperplus) 15 | set_target_properties(clique_corenumber_mex PROPERTIES COMPILE_FLAGS "-fvisibility=default") 16 | set_target_properties(clique_corenumber_mex PROPERTIES OUTPUT_NAME clique_corenumber_mex) 17 | 18 | 19 | if(OPTION_BUILD_PMC_HEU) 20 | matlab_add_mex(NAME pmc_heuristic_mex SRC pmc_heuristic_mex.cpp LINK_TO Eigen3::Eigen pmcheu) 21 | set_target_properties(pmc_heuristic_mex PROPERTIES COMPILE_FLAGS "-fvisibility=default") 22 | set_target_properties(pmc_heuristic_mex PROPERTIES OUTPUT_NAME pmc_heuristic_mex) 23 | endif() 24 | 25 | else() 26 | message(WARNING "MATLAB root directory not found. Will not build MATLAB bindings.") 27 | set(OPTION_BUILD_BINDINGS_MATLAB OFF) 28 | endif() -------------------------------------------------------------------------------- /bindings/matlab/clipperplus_clique_mex.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | * @file clipperplus_clique_mex.cpp 3 | * @brief MATLAB/MEX binding for running CLIPPER+ 4 | * @author Kaveh Fathian 5 | */ 6 | #include 7 | #include 8 | #include 9 | #include 10 | 11 | #include 12 | #include 13 | 14 | #include "clipperplus/clipperplus_clique.h" 15 | #include "mexutils.h" 16 | 17 | void mexFunction(int nlhs, mxArray* plhs[], int nrhs, const mxArray* prhs[]) 18 | { 19 | // nlhs number of expected outputs 20 | // plhs array to be populated by outputs (data passed back to matlab) 21 | // nrhs number of inputs 22 | // prhs array poplulated by inputs (data passed from matlab) 23 | 24 | bool useSparse = false; // as determined by input adj 25 | Eigen::MatrixXd adj; // graph adjacency matrix 26 | Eigen::SparseMatrix adjs; // sparse adjacency matrix 27 | 28 | if (nrhs == 1) { 29 | if (mxIsSparse(prhs[0])) { 30 | adjs = mexMatrixToEigenSparse(prhs[0]); 31 | useSparse = true; 32 | } else if (!mxIsSparse(prhs[0])) { 33 | mexMatrixToEigen(prhs[0], &adj); 34 | } else { 35 | mexErrMsgIdAndTxt("clipperplus:nargin", "adj must be sparse or full matrix."); 36 | } 37 | } else { 38 | mexErrMsgIdAndTxt("clipperplus:nargin", "function only takes the adjacency matrix as input."); 39 | } 40 | 41 | // number of graph nodes 42 | const int nnodes = (useSparse) ? adjs.rows() : adj.rows(); 43 | 44 | const auto t1 = std::chrono::high_resolution_clock::now(); // timer 45 | 46 | // run clipperplus_clique: 47 | auto [clique, certificate] = clipperplus::find_clique(adj); 48 | long clique_size = clique.size(); 49 | 50 | const auto t2 = std::chrono::high_resolution_clock::now(); 51 | const auto duration = std::chrono::duration_cast(t2 - t1); 52 | const double elapsed = static_cast(duration.count()) / 1e6; 53 | 54 | // add 1 to clique indices (because matlab indexing starts at 1) 55 | for (int i = 0; i < clique.size(); i++) { 56 | clique[i] += 1; 57 | } 58 | 59 | if (nlhs >= 1) { 60 | plhs[0] = mxCreateDoubleScalar(static_cast(clique_size)); 61 | } 62 | 63 | if (nlhs >= 2) { 64 | // Create a MATLAB matrix of integers 65 | mxArray* outputclique = mxCreateNumericMatrix(1, clique_size, mxINT32_CLASS, mxREAL); 66 | int* outputData = (int*)mxGetData(outputclique); // Cast to int pointer 67 | std::copy(clique.begin(), clique.end(), outputData); 68 | 69 | // Return the MATLAB matrix 70 | plhs[1] = outputclique; 71 | } 72 | 73 | if (nlhs >= 3) { 74 | plhs[2] = mxCreateDoubleScalar(static_cast(certificate)); 75 | } 76 | 77 | if (nlhs >= 4) { 78 | plhs[3] = mxCreateDoubleScalar(elapsed); 79 | } 80 | 81 | if (nlhs > 4) { 82 | mexErrMsgIdAndTxt("clipperplus:nargout", "Only up to 4 output args supported (clq_size, clq, cert, t)"); 83 | } 84 | 85 | 86 | } //mexFunction 87 | -------------------------------------------------------------------------------- /bindings/matlab/clique_corenumber_mex.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | * @brief MATLAB/MEX binding 3 | * @author Kaveh Fathian 4 | */ 5 | #include 6 | #include 7 | #include 8 | #include 9 | 10 | #include 11 | #include 12 | 13 | #include "clipperplus/clipperplus_clique.h" 14 | #include "mexutils.h" 15 | 16 | void mexFunction(int nlhs, mxArray* plhs[], int nrhs, const mxArray* prhs[]) 17 | { 18 | // nlhs number of expected outputs 19 | // plhs array to be populated by outputs (data passed back to matlab) 20 | // nrhs number of inputs 21 | // prhs array poplulated by inputs (data passed from matlab) 22 | 23 | bool useSparse = false; // as determined by input adj 24 | Eigen::MatrixXd adj; // graph adjacency matrix 25 | Eigen::SparseMatrix adjs; // sparse adjacency matrix 26 | 27 | if (nrhs == 1) { 28 | if (mxIsSparse(prhs[0])) { 29 | adjs = mexMatrixToEigenSparse(prhs[0]); 30 | useSparse = true; 31 | } else if (!mxIsSparse(prhs[0])) { 32 | mexMatrixToEigen(prhs[0], &adj); 33 | } else { 34 | mexErrMsgIdAndTxt("clipperplus:nargin", "adj must be sparse or full matrix."); 35 | } 36 | } else { 37 | mexErrMsgIdAndTxt("clipperplus:nargin", "function only takes the adjacency matrix as input."); 38 | } 39 | 40 | // number of graph nodes 41 | const long nnodes = useSparse ? adjs.rows() : adj.rows(); 42 | 43 | const auto t1 = std::chrono::high_resolution_clock::now(); // timer 44 | 45 | // run clipperplus_clique: 46 | std::vector clique; // initialize index vector of clique 47 | clique.reserve(nnodes); // allocate memory 48 | std::vector core_numbers(nnodes,0); // initialize vector of core numbers 49 | long int core_bound = 0; // initialize max clique upper bound based on max kcore 50 | int chromatic_bound = 0;; // initialize chromatic number upper bound 51 | std::vector node_colors(nnodes, 0); // initialize graph node coloring 52 | 53 | clipperplus::clique_corenumber(adj, clique, core_numbers, 54 | core_bound, node_colors, chromatic_bound); 55 | 56 | long clique_size = clique.size(); 57 | 58 | const auto t2 = std::chrono::high_resolution_clock::now(); 59 | const auto duration = std::chrono::duration_cast(t2 - t1); 60 | const double elapsed = static_cast(duration.count()) / 1e6; 61 | 62 | // add 1 to clique indices (because matlab indexing starts at 1) 63 | for (int& index : clique) { 64 | index += 1; 65 | } 66 | 67 | if (nlhs >= 1) { 68 | plhs[0] = mxCreateDoubleScalar(static_cast(clique_size)); 69 | } 70 | 71 | if (nlhs >= 2) { 72 | // Create a MATLAB matrix of integers 73 | mxArray* outputclique = mxCreateNumericMatrix(1, clique_size, mxINT32_CLASS, mxREAL); 74 | auto outputData = static_cast(mxGetData(outputclique)); // Cast to int pointer 75 | std::copy(clique.begin(), clique.end(), outputData); 76 | 77 | // Return the MATLAB matrix 78 | plhs[1] = outputclique; 79 | } 80 | 81 | if (nlhs >= 3) { 82 | plhs[2] = mxCreateDoubleScalar(elapsed); 83 | } 84 | 85 | if (nlhs > 3) { 86 | mexErrMsgIdAndTxt("nargout", "Only up to 3 output args supported (clq_size, clq, t)"); 87 | } 88 | 89 | 90 | } //mexFunction 91 | -------------------------------------------------------------------------------- /bindings/matlab/clique_optimization_mex.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | * @brief MATLAB/MEX binding 3 | * @author Kaveh Fathian 4 | */ 5 | #include 6 | #include 7 | #include 8 | #include 9 | 10 | #include 11 | #include 12 | 13 | #include "clipperplus/clipperplus_clique.h" 14 | #include "mexutils.h" 15 | 16 | void mexFunction(int nlhs, mxArray* plhs[], int nrhs, const mxArray* prhs[]) 17 | { 18 | // nlhs number of expected outputs 19 | // plhs array to be populated by outputs (data passed back to matlab) 20 | // nrhs number of inputs 21 | // prhs array poplulated by inputs (data passed from matlab) 22 | 23 | bool useSparse = false; // as determined by input adj 24 | Eigen::MatrixXd adj; // graph adjacency matrix 25 | Eigen::SparseMatrix adjs; // sparse adjacency matrix 26 | 27 | if (nrhs == 1) { 28 | if (mxIsSparse(prhs[0])) { 29 | adjs = mexMatrixToEigenSparse(prhs[0]); 30 | useSparse = true; 31 | } else if (!mxIsSparse(prhs[0])) { 32 | mexMatrixToEigen(prhs[0], &adj); 33 | } else { 34 | mexErrMsgIdAndTxt("clipperplus:nargin", "adj must be sparse or full matrix."); 35 | } 36 | } else { 37 | mexErrMsgIdAndTxt("clipperplus:nargin", "function only takes the adjacency matrix as input."); 38 | } 39 | 40 | // number of graph nodes 41 | const int nnodes = (useSparse) ? adjs.rows() : adj.rows(); 42 | 43 | const auto t1 = std::chrono::high_resolution_clock::now(); // timer 44 | 45 | 46 | Eigen::MatrixXd M = adj + Eigen::MatrixXd::Identity(nnodes,nnodes); 47 | Eigen::VectorXd u0 = randvec(nnodes); 48 | std::vector clique = clipperplus::clique_optimization(M, u0, clipperplus::Params()); 49 | long long int clique_size = clique.size(); 50 | 51 | const auto t2 = std::chrono::high_resolution_clock::now(); 52 | const auto duration = std::chrono::duration_cast(t2 - t1); 53 | const double elapsed = static_cast(duration.count()) / 1e6; 54 | 55 | // add 1 to clique indices (because matlab indexing starts at 1) 56 | for (int i = 0; i < clique.size(); i++) { 57 | clique[i] += 1; 58 | } 59 | 60 | if (nlhs >= 1) { 61 | plhs[0] = mxCreateDoubleScalar(static_cast(clique_size)); 62 | } 63 | 64 | if (nlhs >= 2) { 65 | // Create a MATLAB matrix of integers 66 | mxArray* outputclique = mxCreateNumericMatrix(1, clique_size, mxINT32_CLASS, mxREAL); 67 | int* outputData = (int*)mxGetData(outputclique); // Cast to int pointer 68 | std::copy(clique.begin(), clique.end(), outputData); 69 | 70 | // Return the MATLAB matrix 71 | plhs[1] = outputclique; 72 | } 73 | 74 | if (nlhs >= 3) { 75 | plhs[2] = mxCreateDoubleScalar(elapsed); 76 | } 77 | 78 | if (nlhs > 3) { 79 | mexErrMsgIdAndTxt("nargout", "Only up to 3 output args supported (clq_size, clq, t)"); 80 | } 81 | 82 | 83 | } //mexFunction 84 | -------------------------------------------------------------------------------- /bindings/matlab/mexutils.h: -------------------------------------------------------------------------------- 1 | /* 2 | MATLAB/MEX utils for CLIPPER+ bindings 3 | */ 4 | 5 | #pragma once 6 | 7 | #include 8 | #include 9 | #include 10 | #include 11 | #include 12 | #include 13 | 14 | #include 15 | 16 | #include 17 | #include 18 | 19 | using MatlabSparse = Eigen::SparseMatrix::type>; 20 | using SpMat = Eigen::SparseMatrix; 21 | 22 | template 23 | void mapDblBufToEigen(Eigen::Matrix* pmat, double* buf) 24 | { 25 | Eigen::Matrix tmp = Eigen::Map>(buf, pmat->rows(), pmat->cols()); 26 | *pmat = tmp.template cast(); 27 | } 28 | 29 | // ---------------------------------------------------------------------------- 30 | 31 | template 32 | void mapDblBufToEigen(Eigen::Matrix* pmat, double* buf) 33 | { 34 | *pmat = Eigen::Map>(buf, pmat->rows(), pmat->cols()); 35 | } 36 | 37 | // ---------------------------------------------------------------------------- 38 | 39 | template 40 | void mexMatrixToEigen(const mxArray* pa, Eigen::Matrix* pmat, bool checkSize = true) 41 | { 42 | int rows = mxGetM(pa); 43 | int cols = mxGetN(pa); 44 | 45 | if (checkSize && ((r != Eigen::Dynamic && rows != r) || (c != Eigen::Dynamic && cols != c))) { 46 | char BUF[100]; 47 | std::snprintf(BUF, 100, "Expected size (%d x %d) but got (%d x %d)", r, c, rows, cols); 48 | mexErrMsgIdAndTxt("mexutils:mexMatrixToEigen", BUF); 49 | } 50 | 51 | pmat->resize(rows, cols); 52 | 53 | double* buf = (double *)mxGetData(pa); 54 | mapDblBufToEigen(pmat, buf); 55 | } 56 | 57 | // ---------------------------------------------------------------------------- 58 | 59 | Eigen::Map mexMatrixToEigenSparse(const mxArray* pa) 60 | { 61 | mxAssert(mxGetClassID(pa) == mxDOUBLE_CLASS, "Type of the input matrix isn't double"); 62 | const int m = mxGetM(pa); 63 | const int n = mxGetN(pa); 64 | const int nz = mxGetNzmax(pa); 65 | 66 | MatlabSparse::StorageIndex* ir = reinterpret_cast(mxGetIr(pa)); 67 | MatlabSparse::StorageIndex* jc = reinterpret_cast(mxGetJc(pa)); 68 | return Eigen::Map(m, n, nz, jc, ir, mxGetPr(pa)); 69 | } 70 | 71 | // ---------------------------------------------------------------------------- 72 | 73 | Eigen::VectorXd randvec(size_t n) 74 | { 75 | std::random_device rd; 76 | std::mt19937 gen(rd()); 77 | std::uniform_real_distribution dis(0, 1); 78 | 79 | return Eigen::VectorXd::NullaryExpr(n, 1, [&](){ return dis(gen); }); 80 | } 81 | 82 | // ---------------------------------------------------------------------------- 83 | 84 | /** 85 | * @brief Helper class to map MATLAB struct to Invariant Params 86 | * @tparam Params The type of Invariant Params being used 87 | */ 88 | template 89 | class ParamsMap 90 | { 91 | public: 92 | ParamsMap() = default; 93 | ~ParamsMap() = default; 94 | 95 | template 96 | void add_field(const std::string& name, M m) 97 | { 98 | map_.emplace(name, [m](auto& p, const void* v) { p.*m = *static_cast(v); }); 99 | } 100 | 101 | Params extract(const mxArray * pStruct) 102 | { 103 | Params params; 104 | 105 | if (pStruct) { 106 | const int nfields = mxGetNumberOfFields(pStruct); 107 | 108 | for (size_t i=0; isecond(params, value); 119 | } 120 | } 121 | 122 | return params; 123 | } 124 | 125 | private: 126 | using ParamSetHandler = std::function; 127 | std::map map_; 128 | }; -------------------------------------------------------------------------------- /bindings/matlab/pmc_heuristic_mex.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | * @file clipperplus_clique_mex.cpp 3 | * @brief MATLAB/MEX binding for running CLIPPER+ 4 | * @author Kaveh Fathian 5 | */ 6 | #include 7 | #include 8 | #include 9 | #include 10 | 11 | #include 12 | #include 13 | 14 | #include "pmc/pmc_heuristic.h" 15 | #include "mexutils.h" 16 | 17 | void mexFunction(int nlhs, mxArray* plhs[], int nrhs, const mxArray* prhs[]) 18 | { 19 | // nlhs number of expected outputs 20 | // plhs array to be populated by outputs (data passed back to matlab) 21 | // nrhs number of inputs 22 | // prhs array poplulated by inputs (data passed from matlab) 23 | 24 | bool useSparse = false; // as determined by input adj 25 | Eigen::MatrixXd adj; // graph adjacency matrix 26 | Eigen::SparseMatrix adjs; // sparse adjacency matrix 27 | 28 | if (nrhs == 1) { 29 | if (mxIsSparse(prhs[0])) { 30 | adjs = mexMatrixToEigenSparse(prhs[0]); 31 | useSparse = true; 32 | } else if (!mxIsSparse(prhs[0])) { 33 | mexMatrixToEigen(prhs[0], &adj); 34 | } else { 35 | mexErrMsgIdAndTxt("pmcheu:nargin", "adj must be sparse or full matrix."); 36 | } 37 | } else { 38 | mexErrMsgIdAndTxt("pmcheu:nargin", "function only takes the adjacency matrix as input."); 39 | } 40 | 41 | // number of graph nodes 42 | const long nnodes = useSparse ? adjs.rows() : adj.rows(); 43 | 44 | const auto t1 = std::chrono::high_resolution_clock::now(); // timer 45 | 46 | // run pmc heuristic: 47 | int clique_size = 0; 48 | std::vector clique; 49 | pmc::pmc_heuristic(adj, clique_size, clique); 50 | 51 | const auto t2 = std::chrono::high_resolution_clock::now(); 52 | const auto duration = std::chrono::duration_cast(t2 - t1); 53 | const double elapsed = static_cast(duration.count()) / 1e6; 54 | 55 | // add 1 to clique indices (because matlab indexing starts at 1) 56 | for (int& index : clique) { 57 | index += 1; 58 | } 59 | 60 | if (nlhs >= 1) { 61 | plhs[0] = mxCreateDoubleScalar(static_cast(clique_size)); 62 | } 63 | 64 | if (nlhs >= 2) { 65 | // Create a MATLAB matrix of integers 66 | mxArray* outputclique = mxCreateNumericMatrix(1, clique_size, mxINT32_CLASS, mxREAL); 67 | auto outputData = (int*)mxGetData(outputclique); // Cast to int pointer 68 | std::copy(clique.begin(), clique.end(), outputData); 69 | 70 | // Return the MATLAB matrix 71 | plhs[1] = outputclique; 72 | } 73 | 74 | if (nlhs >= 3) { 75 | plhs[2] = mxCreateDoubleScalar(elapsed); 76 | } 77 | 78 | if (nlhs > 3) { 79 | mexErrMsgIdAndTxt("pmcheu:nargout", "Only up to 3 output args supported (clq_size, clq, t)"); 80 | } 81 | 82 | } //mexFunction 83 | -------------------------------------------------------------------------------- /bindings/python/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | set(PYPKG_DIR "${CMAKE_CURRENT_BINARY_DIR}/clipperpluspy") 2 | 3 | pybind11_add_module(py_clipperplus py_clipperplus.cpp) 4 | target_link_libraries(py_clipperplus PUBLIC clipperplus) 5 | set_target_properties(py_clipperplus PROPERTIES OUTPUT_NAME "clipperpluspy") 6 | set_target_properties(py_clipperplus PROPERTIES LIBRARY_OUTPUT_DIRECTORY "${PYPKG_DIR}") 7 | 8 | # copy setup.py file binary dir for install with: pip install . 9 | configure_file(setup.py.in ${CMAKE_CURRENT_BINARY_DIR}/setup.py) 10 | 11 | # Create the Python package -- Note that "." is used to conform to PEP 328 12 | file(WRITE "${PYPKG_DIR}/__init__.py" 13 | "from .clipperpluspy import *\n" 14 | "from .clipperpluspy import __version__\n" 15 | "from .clipperpluspy import __doc__") 16 | 17 | set(DIST "none") 18 | if(UNIX AND NOT APPLE) 19 | execute_process(COMMAND bash -c "lsb_release -cs" OUTPUT_VARIABLE UBUNTU_DIST) 20 | string(STRIP "${UBUNTU_DIST}" UBUNTU_DIST) 21 | set(DIST "${UBUNTU_DIST}") 22 | elseif(APPLE) 23 | # TODO: not very specific... 24 | set(DIST "macos") 25 | elseif(WIN32) 26 | # TODO: not very specific... 27 | set(DIST "win10") 28 | endif() 29 | 30 | set(PKGSTR clipperpluspy-py3-${DIST}-${PROJECT_VERSION}) 31 | add_custom_target(pypkg 32 | DEPENDS py_clipperplus 33 | COMMAND ${CMAKE_COMMAND} -E make_directory ${PKGSTR} 34 | COMMAND ${CMAKE_COMMAND} -E copy setup.py ${PKGSTR}/ 35 | COMMAND ${CMAKE_COMMAND} -E copy_directory ${PYPKG_DIR} ${PKGSTR}/clipperpluspy 36 | COMMAND ${CMAKE_COMMAND} -E tar zcvf ${PKGSTR}.tar.gz ${PKGSTR} 37 | WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}) 38 | 39 | add_custom_target(pip-install 40 | DEPENDS pypkg 41 | COMMAND ${PYTHON_EXECUTABLE} -m pip install . 42 | WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/${PKGSTR} 43 | ) -------------------------------------------------------------------------------- /bindings/python/py_clipperplus.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | * @file py_clipper.cpp 3 | * @brief Python bindings for CLIPPER 4 | * @author Parker Lusk 5 | * @date 28 January 2021 6 | */ 7 | 8 | #include 9 | #include 10 | 11 | #include 12 | 13 | #include 14 | #include 15 | #include 16 | 17 | #include "clipper/clipper.h" 18 | #include "clipper/utils.h" 19 | 20 | #include "wrapper.h" 21 | 22 | 23 | namespace py = pybind11; 24 | using namespace pybind11::literals; 25 | 26 | // ---------------------------------------------------------------------------- 27 | 28 | PYBIND11_MODULE(clipperpluspy, m) 29 | { 30 | m.doc() = "CLIPPER+ is an algorithm for finding maximal cliques in unweighted graphs for outlier-robust global registration."; 31 | m.attr("__version__") = CLIPPERPLUS_VERSION; 32 | 33 | m.def("clipperplus_clique", &Wrapper::clipperplus_clique_wrapper, 34 | "adj"_a, 35 | "Find the densest subgraph of a weighted adjacency matrix."); 36 | m.def("find_heuristic_clique", &Wrapper::find_heuristic_clique_wrapper, 37 | "adj"_a, "clique"_a, 38 | "Find a heuristic maximum clique in a graph."); 39 | m.def("clique_optimization", &Wrapper::clique_optimization_wrapper, 40 | "M"_a, "u0"_a, 41 | "Run original clipper on pruned graph"); 42 | } 43 | -------------------------------------------------------------------------------- /bindings/python/setup.py.in: -------------------------------------------------------------------------------- 1 | from setuptools import setup 2 | 3 | setup( 4 | name='clipperpluspy', 5 | version='${PROJECT_VERSION}', 6 | author='Kaveh Fathian', 7 | author_email='fathian@ariarobotics.com', 8 | description='Robust data association framework', 9 | package_dir={'': '${CMAKE_CURRENT_BINARY_DIR}'}, 10 | packages=['clipperpluspy'], 11 | package_data={'': ['*.so']} 12 | ) -------------------------------------------------------------------------------- /bindings/python/wrapper.h: -------------------------------------------------------------------------------- 1 | /** 2 | * @file wrappers.h 3 | * @brief Wrapper for Clipperplus' C++ functions with parameters passed by reference 4 | */ 5 | 6 | #pragma once 7 | 8 | #include 9 | #include "clipperplus/clipperplus_clique.h" 10 | #include "clipperplus/clique_optimization.h" 11 | 12 | class Wrapper { 13 | public: 14 | static std::tuple, int> clipperplus_clique_wrapper(const Eigen::MatrixXd& adj){ 15 | auto [clique, certificate] = clipperplus::find_clique(adj); 16 | 17 | return std::make_tuple((long)clique.size(), clique, (int)certificate); 18 | } 19 | 20 | static std::vector find_heuristic_clique_wrapper( 21 | const Eigen::MatrixXd& adj, 22 | std::vector& clique 23 | ){ 24 | clique = clipperplus::find_heuristic_clique(adj); 25 | return clique; 26 | } 27 | 28 | static std::tuple> clique_optimization_wrapper( 29 | const Eigen::MatrixXd& M, 30 | const Eigen::VectorXd& u0 31 | ){ 32 | std::vector clique = clipperplus::clique_optimization(M, u0, clipperplus::Params()); 33 | return std::make_tuple(1, clique.size(), clique); 34 | } 35 | 36 | }; 37 | 38 | -------------------------------------------------------------------------------- /cmake/pmcConfig.cmake: -------------------------------------------------------------------------------- 1 | get_filename_component(PMC_CMAKE_DIR "${CMAKE_CURRENT_LIST_FILE}" PATH) 2 | 3 | include(CMakeFindDependencyMacro) 4 | 5 | find_dependency(OpenMP REQUIRED) 6 | 7 | include("${PMC_CMAKE_DIR}/pmcTargets.cmake") 8 | -------------------------------------------------------------------------------- /examples/README.md: -------------------------------------------------------------------------------- 1 | # CLIPPER+ Examples 2 | 3 | Here you can find example codes for running CLIPPER+ and registering pointclouds. Note that in order to run the examples, CLIPPER+ must be compiled with Python/MATLAB binders. 4 | 5 | ### Datasets 6 | 7 | Download the pointcloud datasets from [Google Drive](https://drive.google.com/drive/folders/1-SshbPvfBeVXw3r7OazfwO0A1kwNSy23?usp=sharing). 8 | 9 | Uncompress the dataset and save it in the "data" folder. 10 | 11 | 12 | ### Matlab demos 13 | 14 | There are 2 Matlab demos: 15 | - `demo_clipperp`: For using to CLIPPER+ maximal clique in a graph 16 | - `demo_pointcloud_regist`: For registering pointclouds using the CLIPPER+ maximal clique solution 17 | 18 | 19 | ### Python demos 20 | 21 | Will be added soon. 22 | 23 | 24 | Copyright 2024, Kaveh Fathian. All rights reserved. 25 | 26 | -------------------------------------------------------------------------------- /examples/data/place_datasets_here.txt: -------------------------------------------------------------------------------- 1 | Place the pointcloud datasets in the "data" folder. -------------------------------------------------------------------------------- /examples/demo_clipperp.m: -------------------------------------------------------------------------------- 1 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 2 | % Demo of CLIPPER+ max-clique 3 | % Thid demo is tested in Ubuntu 22.04, Matlab R2023a 4 | % 5 | % Download and uncompress the pointcloud datasets, and place them in the "data" folder 6 | % Download link: https://drive.google.com/drive/folders/1-SshbPvfBeVXw3r7OazfwO0A1kwNSy23?usp=sharing 7 | % Run this demo AFTER compiling CLIPPER+ with MATLAB binders. 8 | % 9 | % 10 | % This Demo was tested in Ubuntu 22.04, and MATLAB R2023a 11 | % (C) Kaveh Fathian, Tyler Summers, 2024 12 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 13 | 14 | addpath("./helpers") 15 | 16 | % add clipper+ library & mex file to path 17 | addpath("../build/"); 18 | addpath("../build/bindings/matlab"); 19 | 20 | adr_data = './data'; % address to dataset 21 | 22 | 23 | %% set benchmark and sequence 24 | 25 | % choose dataset 7 sequence 26 | bench_name = '7-Scenes'; 27 | bench_sequence = 'kitchen'; 28 | 29 | % bench_name = 'Sun3D'; 30 | % bench_sequence = 'sun3d-home_at-home_at_scan1_2013_jan_1'; % {'sun3d-home_at-home_at_scan1_2013_jan_1', 'sun3d-hotel_uc-scan3', 'sun3d-mit_76_studyroom-76-1studyroom2'}; 31 | 32 | % bench_name = 'ETH'; 33 | % bench_sequence = 'gazebo_summer'; % {'gazebo_summer', 'wood_autmn'}; 34 | 35 | 36 | %% matched pointclouds 37 | 38 | % index of matched pointclouds. change to see different matches (matched 39 | % pairs must exist in the dataset folder) 40 | idx1 = 0; 41 | idx2 = 1; 42 | 43 | 44 | %% dataset address 45 | 46 | adr_scans = strcat(adr_data, '/', bench_name, '/', bench_sequence, '/'); 47 | folder_name = strcat('scans_', num2str(idx1), '_', num2str(idx2)); 48 | adr_scan_pair = strcat(adr_scans, folder_name, '/'); 49 | 50 | 51 | %% import data 52 | 53 | fprintf('loading scans %d and %d of in %s dataset.\n', idx1, idx2, bench_name); 54 | 55 | % graph adjacency matrix 56 | fileID = fopen(strcat(adr_scan_pair, 'adj.txt'),'r'); 57 | adj = fscanf(fileID, '%d', Inf); 58 | siz_adj = sqrt(length(adj)); 59 | adj = reshape(adj, [siz_adj, siz_adj]); 60 | fprintf('graph adjacency matrix size = %d\n', siz_adj); 61 | 62 | % ground truth maximum clique and its index (in the adjacency matrix) 63 | fileID = fopen(strcat(adr_scan_pair, 'omega_gt.txt'),'r'); 64 | omega_gt = fscanf(fileID, '%d', Inf).'; 65 | fileID = fopen(strcat(adr_scan_pair, 'omega_gt_idx.txt'),'r'); 66 | omega_gt_idx = fscanf(fileID, '%d', Inf); 67 | fprintf('ground truth clique size = %d\n', omega_gt); 68 | 69 | 70 | %% run Clipper+ 71 | 72 | fprintf('running clipper+ ...\n'); 73 | [omega_hat, clique_idx, certified, runtime] = clipperplus_clique_mex(adj); 74 | 75 | fprintf('clipper+ done\n\n'); 76 | 77 | omega_ratio = omega_hat/omega_gt; 78 | omega_ratio2 = numel(intersect(omega_gt_idx,clique_idx))/omega_gt; 79 | 80 | 81 | fprintf('clipper+ found clique of size %d.\n', omega_hat); 82 | fprintf('ground truth clique size is %d.\n', omega_gt); 83 | 84 | 85 | 86 | -------------------------------------------------------------------------------- /examples/demo_pointcloud_regist.m: -------------------------------------------------------------------------------- 1 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 2 | % Demo of CLIPPER+ max-clique point cloud registration 3 | % Thid demo is tested in Ubuntu 22.04, Matlab R2023a 4 | % 5 | % Download and uncompress the pointcloud datasets, and place them in the "data" folder 6 | % Download link: https://drive.google.com/drive/folders/1-SshbPvfBeVXw3r7OazfwO0A1kwNSy23?usp=sharing 7 | % Run this demo AFTER compiling CLIPPER+ with MATLAB binders. 8 | % 9 | % This Demo was tested in Ubuntu 22.04, and MATLAB R2023a 10 | % (C) Kaveh Fathian, Tyler Summers, 2024 11 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 12 | 13 | addpath("./helpers") 14 | 15 | % add clipper+ library & mex file to path 16 | addpath("../build/"); 17 | addpath("../build/bindings/matlab"); 18 | 19 | adr_data = './data'; % address to dataset 20 | 21 | 22 | %% set benchmark and sequence 23 | 24 | % choose dataset 7 sequence 25 | bench_name = '7-Scenes'; 26 | bench_sequence = 'kitchen'; 27 | 28 | % bench_name = 'Sun3D'; 29 | % bench_sequence = 'sun3d-home_at-home_at_scan1_2013_jan_1'; % {'sun3d-home_at-home_at_scan1_2013_jan_1', 'sun3d-hotel_uc-scan3', 'sun3d-mit_76_studyroom-76-1studyroom2'}; 30 | 31 | % bench_name = 'ETH'; 32 | % bench_sequence = 'gazebo_summer'; % {'gazebo_summer', 'wood_autmn'}; 33 | 34 | 35 | %% matched pointclouds 36 | 37 | % index of matched pointclouds. change to see different matches (matched 38 | % pairs must exist in the dataset folder) 39 | idx1 = 0; 40 | idx2 = 1; 41 | 42 | 43 | %% dataset address 44 | 45 | adr_scans = strcat(adr_data, '/', bench_name, '/', bench_sequence, '/'); 46 | folder_name = strcat('scans_', num2str(idx1), '_', num2str(idx2)); 47 | adr_scan_pair = strcat(adr_scans, folder_name, '/'); 48 | 49 | 50 | %% import data 51 | 52 | fprintf('loading scans %d and %d of in %s dataset.\n', idx1, idx2, bench_name); 53 | 54 | % putative and inlier associations 55 | fileID = fopen(strcat(adr_scan_pair, 'assoc_putative.txt'),'r'); 56 | assoc_putative = fscanf(fileID, '%d %d', [2, Inf]).'; 57 | fileID = fopen(strcat(adr_scan_pair, 'assoc_inliers.txt'),'r'); 58 | assoc_inliers = fscanf(fileID, '%d %d', [2, Inf]).'; 59 | fprintf('number of putative associations = %d\n', size(assoc_putative,1)); 60 | fprintf('number of inlier associations = %d\n', size(assoc_inliers,1)); 61 | 62 | % feature point coordinates in the pointclouds 63 | fileID = fopen(strcat(adr_scan_pair, 'feat1.txt'),'r'); 64 | feat1 = fscanf(fileID, '%f %f %f', [3, Inf]).'; 65 | fileID = fopen(strcat(adr_scan_pair, 'feat2.txt'),'r'); 66 | feat2 = fscanf(fileID, '%f %f %f', [3, Inf]).'; 67 | 68 | % ground truth relative pose 69 | fileID = fopen(strcat(adr_scan_pair, 'transf_gt.txt'),'r'); 70 | transf_gt = fscanf(fileID, '%f', [4, Inf]).'; 71 | 72 | % graph adjacency matrix 73 | fileID = fopen(strcat(adr_scan_pair, 'adj.txt'),'r'); 74 | adj = fscanf(fileID, '%d', Inf); 75 | siz_adj = sqrt(length(adj)); 76 | adj = reshape(adj, [siz_adj, siz_adj]); 77 | fprintf('graph adjacency matrix size = %d\n', siz_adj); 78 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | 86 | 87 | 88 | 89 | 90 | 91 | 92 | 93 | 94 | 95 | 96 | 97 | 98 | 99 | 100 | 101 | 102 | 103 | 104 | 105 | %% run Clipper+ 106 | 107 | fprintf('running clipper+ ...\n'); 108 | [omega_hat, clique_idx, certified, runtime] = clipperplus_clique_mex(adj); 109 | 110 | fprintf('clipper+ done\n\n'); 111 | 112 | 113 | %% Display parameters 114 | 115 | disp_figs = false; % general display flag, if 'false' no figs will show 116 | color_pt1 = [0, 0.4470, 0.7410]; % color of point cloud 1 117 | color_pt2 = [0.5412, 0.1686, 0.8863]; % color of point cloud 2 118 | color_background = [1, 1, 1]; % backgroud color of point cloud figure 119 | 120 | bench_file_format = '.ply'; 121 | if strcmp(bench_name, '7-Scenes') || strcmp(bench_name, 'Sun3D') 122 | bench_file_name = 'cloud_bin_'; 123 | end 124 | if strcmp(bench_name, 'ETH') 125 | bench_file_name = 'Hokuyo_'; 126 | end 127 | 128 | %% disply pointclouds 129 | 130 | adr_pt = strcat(adr_scans, bench_file_name); % address to point cloud files 131 | fprintf('reading pointclouds...\n') 132 | pt1_orig = pcread( strcat(adr_pt, num2str(idx1), bench_file_format) ); % first point cloud 133 | pt2_orig = pcread( strcat(adr_pt, num2str(idx2), bench_file_format) ); % second point cloud 134 | 135 | % add color 136 | pt1_orig.Color = repmat(color_pt1,pt1_orig.Count,1); 137 | pt2_orig.Color = repmat(color_pt2,pt2_orig.Count,1); 138 | 139 | % display the pt clouds 140 | figure; 141 | pcshow(pt1_orig, 'MarkerSize',3, 'BackgroundColor', color_background); 142 | title('1st pointcloud'); 143 | view([0.2822 -66.9150]) 144 | 145 | figure; 146 | pcshow(pt2_orig, 'MarkerSize',3, 'BackgroundColor', color_background); 147 | title('2nd pointcloud'); 148 | view([0.2822 -66.9150]) 149 | 150 | 151 | 152 | %% display aligned point clouds based on CLIPPER solution 153 | 154 | % point cloud alignment 155 | assoc_maxclq = assoc_putative(clique_idx,:); % max clique associations 156 | feat1_maxclq = feat1(assoc_maxclq(:,1),:); % selected features 157 | feat2_maxclq = feat2(assoc_maxclq(:,2),:); % selected features 158 | [rot, trans] = arun(feat1_maxclq.', feat2_maxclq.'); % alignment rotation/translation from Arun's method 159 | 160 | % check if correct solution found 161 | rot_gt = transf_gt(1:3,1:3); % ground truth rotation 162 | trans_gt = transf_gt(1:3,4); % ground truth translation 163 | rot_err = norm( rotmat2vec3d(rot*rot_gt.') ); % rotation error in radians 164 | trans_err = norm( trans - trans_gt); % translation error in meters 165 | 166 | thresh_rot_err = 0.0873; % (in radian) 0.0873 radians is 5 degrees 167 | thresh_trans_err = 2*0.05; % (in meters) 168 | if (rot_err < thresh_rot_err) && (trans_err < thresh_trans_err) 169 | fprintf('point clouds correctly registered by max clique solution\n') 170 | else 171 | fprintf('point clouds wrongly registered by max clique solution\n') 172 | end 173 | fprintf('rotation error=%g radians; translation error=%g meters\n', rot_err,trans_err); 174 | 175 | % transform point cloud 176 | transf = [rot, trans; [0 0 0 1]]; 177 | tform = rigidtform3d(transf); % matlab rigid transform 178 | pt2_transf = pctransform(pt2_orig,tform); % transformed point cloud 179 | feat2_maxclq_transf = transf * [feat2_maxclq.'; ones(1, size(feat2_maxclq,1))]; % transform feature points 180 | feat2_maxclq_transf = feat2_maxclq_transf(1:3,:).'; 181 | residue_vec = sqrt(sum((feat1_maxclq - feat2_maxclq_transf).^2,2)); % distance between aligned features 182 | fprintf('max distance error between aligned features = %g \n',max(residue_vec)) 183 | 184 | % display aligned pointclouds and aligned features (based on max clique solution) 185 | figure; 186 | pt1_feat = pointCloud(feat1_maxclq, 'Color',[1,0,0]); 187 | pt2_feat = pointCloud(feat2_maxclq_transf, 'Color',[0,1,0]); 188 | 189 | hold on 190 | pcshow(pt1_orig, 'MarkerSize',30, 'BackgroundColor', color_background); 191 | pcshow(pt2_transf, 'MarkerSize',30, 'BackgroundColor', color_background); 192 | pcshow(pt1_feat, 'MarkerSize',500, 'BackgroundColor', color_background); 193 | pcshow(pt2_feat, 'MarkerSize',500, 'BackgroundColor', color_background); 194 | hold off 195 | title('Aligned point clouds using CLIPPER ') 196 | 197 | 198 | -------------------------------------------------------------------------------- /examples/helpers/affinity_matrix.m: -------------------------------------------------------------------------------- 1 | %% Function to generate affinity matrix and distinctness constraint matrix 2 | % 3 | % Inputs: 4 | % - A: Set of associations 5 | % - P1,P2: Point clouds 6 | % 7 | % Output: 8 | % - M: Affinity matrix 9 | % - C: Constraint matrix (distinctness & consistency) 10 | % 11 | % 12 | function [M, C] = affinity_matrix(A, P1,P2, eps, sig) 13 | 14 | nA = size(A,1); % Total number of associations 15 | 16 | % Preallocate matrices (symmetric, use sparse for speed?) 17 | M = eye(nA)*0.5; % M will be added to its transpose, so diagonals will become 1 18 | C = tril(true(nA)) - 0.5*eye(nA); % C will be added to its transpose, so diagonal will become 1 19 | 20 | % list all combinations of associations (in vector) 21 | disp('Generating combination of associations...'); 22 | comb = zeros(nA*(nA-1)/2, 2); 23 | itr = 0; 24 | for i = 1 : nA-1 25 | jcol = (i+1:nA).'; 26 | icol = i*ones(nA-i,1); 27 | comb(itr+1 : itr+(nA-i), :) = [jcol, icol]; 28 | itr = itr+(nA-i); 29 | % for j = i+1 : nA 30 | % itr = itr + 1; 31 | % comb(itr,:) = [j,i]; 32 | % end 33 | end 34 | 35 | disp('Computing consistency scores...'); 36 | % end points of the line segments corresponding to association pairs 37 | p1_a = P1(A(comb(:,1), 1), :); 38 | p1_b = P1(A(comb(:,2), 1), :); 39 | 40 | % end points of the line segments corresponding to association pairs 41 | p2_a = P2(A(comb(:,1), 2), :); 42 | p2_b = P2(A(comb(:,2), 2), :); 43 | 44 | 45 | % length of line segments 46 | d1 = sqrt( sum( (p1_a - p1_b).^2 ,2) ); 47 | d2 = sqrt( sum( (p2_a - p2_b).^2 ,2) ); 48 | 49 | % residual distance 50 | resid = abs(d1-d2); 51 | 52 | Mvec = zeros(size(resid)); % lower triangular part of M matrix 53 | Cvec = ones(size(resid)); % lower triangular part of C matrix 54 | 55 | idx = (resid < eps); % index of consistent associations 56 | Mvec(idx) = exp(-resid(idx).^2. / (2 * sig^2)); % consistency score 57 | Cvec(~idx) = 0; % inconsistent associations 58 | 59 | % inconsistent associations that start/end at same points (not one-to-one) 60 | idx_z1 = (d1 == 0); 61 | idx_z2 = (d2 == 0); 62 | Mvec(idx_z1) = 0; 63 | Mvec(idx_z2) = 0; 64 | Cvec(idx_z1) = 0; 65 | Cvec(idx_z2) = 0; 66 | 67 | % put vectorized values into the lower triangular part 68 | M( tril( (true(nA)-eye(nA))>0.5 ) ) = Mvec; 69 | C( tril( (true(nA)-eye(nA))>0.5 ) ) = Cvec; 70 | 71 | % Make matrices symmetric 72 | M = M + M.'; 73 | C = C + C.'; 74 | 75 | disp('Affinity matrix constructed.'); 76 | 77 | 78 | -------------------------------------------------------------------------------- /examples/helpers/arun.m: -------------------------------------------------------------------------------- 1 | % Arun (or Kabsch) algorithm to minimize ||q - (Rp + t)||^2 2 | % inputs: p,q: dxn matrices, coordinates of n points that are d-dimensional (d=2 or 3) 3 | function [R, t] = arun(q, p) 4 | 5 | % ASSUME: q, p are dxn (d: 2D or 3D) 6 | d = size(q,1); 7 | 8 | % shift point clouds by centroids 9 | mu_q = mean(q,2); % (rowwise) 10 | mu_p = mean(p,2); % (rowwise) 11 | Q = q - mu_q; 12 | P = p - mu_p; 13 | 14 | % construct H matrix (dxd) 15 | H = Q * P'; 16 | 17 | % perform SVD of H 18 | [U,~,V] = svd(H); 19 | D = eye(size(H)); 20 | D(d,d) = det(U*V'); 21 | 22 | % solve rotation-only problem 23 | R = U*D*V'; 24 | 25 | % solve translation 26 | t = mu_q - R*mu_p; 27 | end -------------------------------------------------------------------------------- /examples/python/demo_clipperp.py: -------------------------------------------------------------------------------- 1 | import numpy as np 2 | import networkx as nx 3 | import matplotlib.pyplot as plt 4 | 5 | import sys, os, pathlib, time, argparse 6 | sys.path.append(os.path.abspath('../../build/bindings/python/clipperpluspy/')) 7 | 8 | import clipperpluspy 9 | 10 | 11 | parser = argparse.ArgumentParser() 12 | parser.add_argument('--folder', type=str, default='../data') 13 | parser.add_argument('--name', type=str, default='7-Scenes') 14 | parser.add_argument('--sequence', type=str, default='kitchen') 15 | parser.add_argument('idx1', type=int) 16 | parser.add_argument('idx2', type=int) 17 | args = parser.parse_args() 18 | 19 | 20 | FOLDER_PATH = pathlib.Path(args.folder) / args.name / args.sequence / f'scans_{args.idx1}_{args.idx2}' 21 | print(f'loading scans {args.idx1} and {args.idx2} of in {args.name} dataset.') 22 | 23 | 24 | adj = np.loadtxt(FOLDER_PATH / 'adj.txt') 25 | print(f'Loaded adj matrix of size {adj.shape}') 26 | 27 | 28 | #NOTE: matlab indices start from 1 29 | omega_gt_idx = np.loadtxt(FOLDER_PATH / 'omega_gt_idx.txt').astype(int) - 1 30 | 31 | print('CLIPPER+ start') 32 | start_time = time.perf_counter() 33 | clique_size, clique, certified = clipperpluspy.clipperplus_clique(adj) 34 | end_time = time.perf_counter() 35 | print(f'CLIPPER+ end took {end_time - start_time: 0.03f}s') 36 | 37 | intersect = set(clique) & set(omega_gt_idx) 38 | 39 | print(f'CLIPPER+ found clique of size {clique_size}'); 40 | print(f'ground truth clique size is {len(omega_gt_idx)}.'); 41 | 42 | print() 43 | print(f'Omega ratio: {len(clique) / len(omega_gt_idx):0.02f}') 44 | print(f'Precision: {len(intersect) / len(clique):0.02f} ') 45 | print(f'Recall: {len(intersect) / len(omega_gt_idx):0.02f}') 46 | 47 | -------------------------------------------------------------------------------- /examples/python/demo_pointcloud_register.py: -------------------------------------------------------------------------------- 1 | import numpy as np 2 | import open3d as o3d 3 | from scipy.spatial.transform import Rotation 4 | 5 | 6 | import sys, os, pathlib, time, argparse 7 | sys.path.append(os.path.abspath('../../build/bindings/python/clipperpluspy/')) 8 | 9 | import clipperpluspy 10 | 11 | 12 | parser = argparse.ArgumentParser() 13 | parser.add_argument('--folder', type=str, default='../data') 14 | parser.add_argument('--name', type=str, default='7-Scenes') 15 | parser.add_argument('--sequence', type=str, default='kitchen') 16 | parser.add_argument('idx1', type=int) 17 | parser.add_argument('idx2', type=int) 18 | parser.add_argument('--threshold', type=float, default=0.05) 19 | args = parser.parse_args() 20 | 21 | 22 | THREDHOLD = args.threshold 23 | FOLDER_PATH = pathlib.Path(args.folder) / args.name / args.sequence / f'scans_{args.idx1}_{args.idx2}' 24 | print(f'loading scans {args.idx1} and {args.idx2} of in {args.name} dataset.') 25 | 26 | source_points = np.loadtxt(FOLDER_PATH / 'feat2.txt') 27 | target_points = np.loadtxt(FOLDER_PATH / 'feat1.txt') 28 | 29 | #NOTE: matlab indices start from 1 30 | associations = np.loadtxt(FOLDER_PATH / 'assoc_putative.txt').astype(int) - 1 31 | source_indices, target_indices = associations[:, 1], associations[:, 0] 32 | 33 | true_associations = np.loadtxt(FOLDER_PATH / 'assoc_inliers.txt').astype(int) - 1 34 | 35 | source_distance_matrix = np.linalg.norm(source_points[source_indices, None] - source_points[source_indices], axis=2) 36 | target_distance_matrix = np.linalg.norm(target_points[target_indices, None] - target_points[target_indices], axis=2) 37 | consistency_matrix = np.abs(source_distance_matrix - target_distance_matrix) 38 | 39 | adj = (consistency_matrix <= THREDHOLD).astype(float) 40 | for x in np.unique(source_indices): 41 | i, = np.where(source_indices == x) 42 | adj[np.ix_(i, i)] = 0 43 | 44 | 45 | for x in np.unique(target_indices): 46 | j, = np.where(target_indices == x) 47 | adj[np.ix_(j, j)] = 0 48 | 49 | 50 | X = np.arange(len(target_indices)) 51 | adj[X, X] = 0 52 | 53 | 54 | omega_gt_idx = np.loadtxt(FOLDER_PATH / 'omega_gt_idx.txt').astype(int) - 1 55 | 56 | print('CLIPPER+ start') 57 | start_time = time.perf_counter() 58 | clique_size, clique, certified = clipperpluspy.clipperplus_clique(adj) 59 | end_time = time.perf_counter() 60 | print(f'CLIPPER+ end took {end_time - start_time: 0.03f}s') 61 | 62 | intersect = set(clique) & set(omega_gt_idx) 63 | 64 | print(f'CLIPPER+ found clique of size {clique_size}'); 65 | print(f'ground truth clique size is {len(omega_gt_idx)}.'); 66 | 67 | print() 68 | print(f'Omega ratio: {len(clique) / len(omega_gt_idx):0.02f}') 69 | print(f'Precision: {len(intersect) / len(clique):0.02f} ') 70 | print(f'Recall: {len(intersect) / len(omega_gt_idx):0.02f}') 71 | 72 | 73 | 74 | source_indices = source_indices[clique] 75 | target_indices = target_indices[clique] 76 | 77 | correspondance = np.vstack([source_indices, target_indices]) 78 | correspondance = o3d.utility.Vector2iVector(correspondance.T) 79 | 80 | 81 | source = o3d.geometry.PointCloud() 82 | source.colors = o3d.utility.Vector3dVector([[1, 0, 0] for i in range(len(source_points))]) 83 | source.points = o3d.utility.Vector3dVector(source_points) 84 | 85 | target = o3d.geometry.PointCloud() 86 | target.points = o3d.utility.Vector3dVector(target_points) 87 | target.colors = o3d.utility.Vector3dVector([[0, 0, 1] for i in range(len(target_points))]) 88 | 89 | 90 | ground_transformation = np.loadtxt(FOLDER_PATH / 'transf_gt.txt') 91 | gt_R, gt_t = ground_transformation[:3, :3], ground_transformation[:3, 3] 92 | 93 | 94 | T = o3d.pipelines.registration.TransformationEstimationPointToPoint(False).compute_transformation( 95 | source, 96 | target, 97 | correspondance 98 | ) 99 | R, t = T[:3, :3], T[:3, 3] 100 | 101 | print(f'Translation error = {np.linalg.norm(t - gt_t):0.02f}m') 102 | 103 | rotation_diff = Rotation.from_matrix(R.T @ gt_R) 104 | rotation_diff = rotation_diff.as_euler('xyz', degrees=True) 105 | print(f'Rotation error = {np.linalg.norm(rotation_diff):0.02f} deg') 106 | 107 | 108 | n = len(source_indices) 109 | points = np.concatenate((source_points[source_indices] @ R.T + t, target_points[target_indices]), axis=0) 110 | lines = [] 111 | for i in range(n): 112 | lines.append([i, i + n]) 113 | 114 | colors = [[0, 1, 0] for i in range(len(lines))] 115 | 116 | line_set = o3d.geometry.LineSet( 117 | points=o3d.utility.Vector3dVector(points), 118 | lines=o3d.utility.Vector2iVector(lines), 119 | ) 120 | line_set.colors = o3d.utility.Vector3dVector(colors) 121 | 122 | o3d.visualization.draw_geometries([source.transform(T), target, line_set]) 123 | 124 | -------------------------------------------------------------------------------- /include/clipperplus/clipperplus_clique.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include 4 | #include 5 | #include 6 | 7 | #include "clipperplus/clique_optimization.h" 8 | #include "clipperplus/clipperplus_heuristic.h" 9 | #include "clipperplus/utils.h" 10 | 11 | 12 | namespace clipperplus 13 | { 14 | 15 | enum class CERTIFICATE 16 | { 17 | NONE, 18 | HEURISTIC, 19 | CORE_BOUND, 20 | CHROMATIC_BOUND 21 | }; 22 | 23 | std::pair, CERTIFICATE> find_clique(const Graph &graph); 24 | 25 | } 26 | -------------------------------------------------------------------------------- /include/clipperplus/clipperplus_graph.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include 4 | #include 5 | #include 6 | 7 | 8 | namespace clipperplus 9 | { 10 | 11 | using Node = int; 12 | using Edge = std::pair; 13 | using Neighborlist = std::vector; 14 | 15 | 16 | class Graph 17 | { 18 | public: 19 | Graph() = default; 20 | Graph(Eigen::MatrixXd adj_matrix); 21 | // static Graph from_list(const std::vector &adj_list); 22 | 23 | int size() const; 24 | int degree(Node v) const; 25 | std::vector degrees() const; 26 | 27 | const std::vector &neighbors(Node v) const; 28 | 29 | inline bool is_edge(Node u, Node v) const 30 | { 31 | return adj_matrix(u, v) != 0; 32 | } 33 | 34 | void merge(const Graph &g); 35 | Graph induced(const std::vector &nodes) const; 36 | 37 | int max_core_number() const; 38 | const std::vector &get_core_numbers() const; 39 | const std::vector &get_core_ordering() const; 40 | 41 | const Eigen::MatrixXd &get_adj_matrix() const; 42 | 43 | private: 44 | void calculate_kcores() const; 45 | 46 | private: 47 | Eigen::MatrixXd adj_matrix; 48 | std::vector adj_list; 49 | 50 | mutable std::vector kcore_ordering; 51 | mutable std::vector kcore; 52 | }; 53 | 54 | 55 | } 56 | -------------------------------------------------------------------------------- /include/clipperplus/clipperplus_heuristic.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | 9 | #include "clipperplus/clipperplus_graph.h" 10 | 11 | namespace clipperplus 12 | { 13 | 14 | std::vector find_heuristic_clique( 15 | const clipperplus::Graph &graph, 16 | int upper_bound = -1, 17 | int lower_bound = 0 18 | ); 19 | 20 | 21 | int estimate_chormatic_number_welsh_powell(const Graph &graph); 22 | 23 | 24 | } 25 | -------------------------------------------------------------------------------- /include/clipperplus/clique_optimization.h: -------------------------------------------------------------------------------- 1 | // for CLIPPER (based on Belachew) optimization-based clique algorithm 2 | #pragma once 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | 9 | #include "clipperplus/utils.h" 10 | 11 | 12 | namespace clipperplus 13 | { 14 | 15 | struct Params { 16 | // gradient descent parameters 17 | double tol_u = 1e-8; // (1e-8) stop innerloop when change in u < tol 18 | double tol_F = 1e-9; // (1e-9) stop innerloop when change in F < tol 19 | int maxiniters = 200; // max num of gradient ascent steps for each d 20 | int maxoliters = 1000; // max num of outer loop iterations to find d 21 | // line search parameters 22 | double beta = 0.5; // backtracking step size reduction, in (0, 1) 23 | double sigma = 0.01; // threshold of armijo condition 24 | 25 | /* maximum number of line search iters per grad step 26 | note: do NOT choose large number (>30), or otherwise 27 | alpha stepsize will become zero and line search will get stuck */ 28 | int maxlsiters = 20; 29 | double minalpha = 1e-9; // minimum value of alpha for line search 30 | double maxalpha = 2; // maximum value of alpha for line search 31 | 32 | double eps = 1e-9; // (1e-9) numerical threshold around 0 (default 1e-9) 33 | }; 34 | 35 | std::vector clique_optimization(const Eigen::MatrixXd& M, const Eigen::VectorXd& u0, const Params ¶ms); 36 | 37 | } 38 | -------------------------------------------------------------------------------- /include/clipperplus/debug.h: -------------------------------------------------------------------------------- 1 | /* 2 | Using the debug macro in the code: 3 | Surround the debugging code with #ifdef and #endif directives based 4 | on the state of the DEBUG macro. This will include or exclude the 5 | debugging code depending on whether the macro is defined. 6 | 7 | Compile with or without the -D flag: 8 | To enable or disable debugging, you can compile your code with or 9 | without the -D flag, which defines or undefines the DEBUG macro, respectively. 10 | 11 | */ 12 | 13 | // debug.h 14 | #ifndef DEBUG_H 15 | #define DEBUG_H 16 | 17 | // Uncomment the line below to enable debugging 18 | // #define DEBUG 19 | #define DEBUG_TIMING 20 | 21 | #endif // DEBUG_H 22 | 23 | -------------------------------------------------------------------------------- /include/clipperplus/utils.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include 4 | #include 5 | #include 6 | 7 | namespace clipperplus::utils 8 | { 9 | 10 | /** 11 | * @brief Select the elements of a vector x given an indicator vector. 12 | * 13 | * @param[in] x Vector to select elements of 14 | * @param[in] ind The indicator vector 15 | * 16 | * @return Vector of selected elements, with size <= x.size 17 | */ 18 | Eigen::VectorXd selectFromIndicator( 19 | const Eigen::VectorXd& x, 20 | const Eigen::VectorXi& ind); 21 | 22 | 23 | 24 | std::vector findIndicesWhereAboveThreshold( 25 | const Eigen::VectorXd& x, 26 | double thr 27 | ); 28 | } 29 | -------------------------------------------------------------------------------- /src/clipperplus_clique.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | computes a maximal clique in graph, and certifies if it's maximum clique 3 | 4 | Author: kaveh fathian (kavehfathian@gmail.com) 5 | */ 6 | 7 | #include "clipperplus/clipperplus_heuristic.h" 8 | #include "clipperplus/clipperplus_clique.h" 9 | 10 | namespace clipperplus 11 | { 12 | 13 | 14 | std::pair, CERTIFICATE> find_clique(const Graph &graph) 15 | { 16 | int n = graph.size(); 17 | 18 | auto chromatic_welsh = estimate_chormatic_number_welsh_powell(graph); 19 | auto k_core_bound = graph.max_core_number() + 1; 20 | 21 | auto heuristic_clique = find_heuristic_clique(graph); 22 | if(heuristic_clique.size() == std::min({k_core_bound, chromatic_welsh})) { 23 | return {heuristic_clique, CERTIFICATE::HEURISTIC}; 24 | } 25 | 26 | std::vector core_number = graph.get_core_numbers(); 27 | std::vector keep, keep_pos(n, -1); 28 | for(Node i = 0, j = 0; i < n; ++i) { 29 | if(core_number[i] + 1 >= heuristic_clique.size()) { 30 | keep.push_back(i); 31 | keep_pos[i] = j++; 32 | } 33 | } 34 | 35 | Eigen::MatrixXd M_pruned = graph.get_adj_matrix()(keep, keep); 36 | M_pruned.diagonal().setOnes(); 37 | 38 | Eigen::VectorXd u0 = Eigen::VectorXd::Ones(keep.size()); 39 | 40 | for(auto v : heuristic_clique) { 41 | assert(keep_pos[v] >= 0); 42 | u0(keep_pos[v]) = 0; 43 | } 44 | u0.normalize(); 45 | 46 | auto clique_optim_pruned = clipperplus::clique_optimization(M_pruned, u0, Params()); 47 | std::vector optimal_clique; 48 | if(clique_optim_pruned.size() < heuristic_clique.size()) { 49 | optimal_clique = heuristic_clique; 50 | } else { 51 | for(auto v : clique_optim_pruned) { 52 | assert(v >= 0 && v < keep.size()); 53 | optimal_clique.push_back(keep[v]); 54 | } 55 | } 56 | 57 | 58 | auto certificate = CERTIFICATE::NONE; 59 | if(optimal_clique.size() == k_core_bound) { 60 | certificate = CERTIFICATE::CORE_BOUND; 61 | } else if(optimal_clique.size() == chromatic_welsh) { 62 | certificate = CERTIFICATE::CHROMATIC_BOUND; 63 | } 64 | 65 | return {optimal_clique, certificate}; 66 | } 67 | 68 | } -------------------------------------------------------------------------------- /src/clipperplus_graph.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "clipperplus/clipperplus_graph.h" 3 | 4 | 5 | namespace clipperplus 6 | { 7 | 8 | 9 | Graph::Graph(Eigen::MatrixXd adj) : adj_matrix(std::move(adj)), adj_list(adj_matrix.rows()) 10 | { 11 | int nnodes = adj_matrix.rows(); 12 | for(int i = 0; i < nnodes; ++i) { 13 | for(int j = 0; j < nnodes; ++j) { 14 | if(adj_matrix(i, j) != 0) { 15 | adj_list[i].push_back(j); 16 | } 17 | } 18 | } 19 | } 20 | 21 | 22 | 23 | 24 | const std::vector &Graph::neighbors(Node v) const 25 | { 26 | assert(v < adj_list.size()); 27 | return adj_list[v]; 28 | } 29 | 30 | 31 | int Graph::degree(Node v) const 32 | { 33 | assert(v < adj_list.size()); 34 | return adj_list[v].size(); 35 | } 36 | 37 | 38 | std::vector Graph::degrees() const 39 | { 40 | int nnodes = adj_list.size(); 41 | std::vector degrees(adj_list.size()); 42 | for(int i = 0; i < nnodes; ++i) { 43 | degrees[i] = degree(i); 44 | } 45 | return degrees; 46 | } 47 | 48 | 49 | void Graph::merge(const Graph &g) 50 | { 51 | assert(adj_list.size() == g.adj_list.size()); 52 | for(int i = 0; i < adj_list.size(); ++i) { 53 | adj_list[i].insert( 54 | adj_list[i].end(), 55 | g.adj_list[i].begin(), g.adj_list[i].end() 56 | ); 57 | 58 | adj_matrix(i, g.adj_list[i]).setOnes(); 59 | } 60 | 61 | kcore.clear(); 62 | kcore_ordering.clear(); 63 | } 64 | 65 | 66 | Graph Graph::induced(const std::vector &nodes) const 67 | { 68 | int n = size(); 69 | 70 | auto g = Graph(); 71 | g.adj_matrix = adj_matrix(nodes, nodes); 72 | 73 | 74 | std::vector keep(size(), -1); 75 | for(Node i = 0; i < nodes.size(); ++i) { 76 | keep[nodes[i]] = i; 77 | } 78 | 79 | g.adj_list = std::vector(nodes.size()); 80 | for(Node v = 0; v < n; ++v) { 81 | if(keep[v] < 0) { 82 | continue; 83 | } 84 | 85 | for(auto u : neighbors(v)) { 86 | if(keep[u] >= 0) { 87 | g.adj_list[keep[v]].push_back((Node)keep[u]); 88 | } 89 | } 90 | } 91 | 92 | return g; 93 | } 94 | 95 | 96 | int Graph::size() const 97 | { 98 | return adj_list.size(); 99 | } 100 | 101 | 102 | int Graph::max_core_number() const 103 | { 104 | if(kcore.empty()) { 105 | calculate_kcores(); 106 | } 107 | return kcore[kcore_ordering.back()]; 108 | } 109 | 110 | 111 | const std::vector &Graph::get_core_numbers() const 112 | { 113 | if(kcore.empty()) { 114 | calculate_kcores(); 115 | } 116 | return kcore; 117 | } 118 | 119 | 120 | const std::vector &Graph::get_core_ordering() const 121 | { 122 | if(kcore.empty()) { 123 | calculate_kcores(); 124 | } 125 | return kcore_ordering; 126 | } 127 | 128 | 129 | const Eigen::MatrixXd &Graph::get_adj_matrix() const 130 | { 131 | return adj_matrix; 132 | } 133 | 134 | 135 | void Graph::calculate_kcores() const 136 | { 137 | int n = size(); 138 | auto degree = degrees(); 139 | auto max_degree = *std::max_element(degree.begin(), degree.end()); 140 | 141 | // prepare for bucket sort by degree 142 | // pos[i] is the position of v_i on the sorted array 143 | // If you consider `pos` as an permutation `order` essentially is pos^-1 144 | std::vector pos(n, 0); 145 | kcore_ordering.resize(n); 146 | 147 | std::vector bin(max_degree + 1, 0); 148 | for(auto d : degree) { 149 | ++bin[d]; 150 | } 151 | 152 | int start = 0; 153 | for(int d = 0; d < max_degree + 1; ++d) { 154 | auto num = bin[d]; 155 | bin[d] = start; 156 | start += num; 157 | } 158 | 159 | // bucket sort: 160 | for(int v = 0; v < n; ++v) { 161 | pos[v] = bin[degree[v]]; 162 | kcore_ordering[pos[v]] = v; 163 | ++bin[degree[v]]; 164 | } 165 | 166 | for(int d = max_degree; d > 0; --d) { 167 | bin[d] = bin[d - 1]; 168 | } 169 | bin[0] = 0; 170 | 171 | // iteratively remove edges from v with lowest degree 172 | for(auto v : kcore_ordering) { 173 | for(auto u : neighbors(v)) { // remove e = (v, u) 174 | if(degree[v] >= degree[u]) { 175 | continue; 176 | } 177 | 178 | // update sorted array: pos, order bin 179 | // find first element in sorted array with d[w] = d[u] 180 | auto pos_w = bin[degree[u]]; 181 | auto w = kcore_ordering[pos_w]; 182 | 183 | // swap their pose and order 184 | if(w != u) { 185 | kcore_ordering[pos[u]] = w; 186 | kcore_ordering[pos[w]] = u; 187 | std::swap(pos[u], pos[w]); 188 | } 189 | 190 | 191 | ++bin[degree[u]]; 192 | --degree[u]; 193 | } 194 | } 195 | 196 | kcore = std::move(degree); 197 | } 198 | 199 | 200 | } 201 | 202 | 203 | -------------------------------------------------------------------------------- /src/clipperplus_heuristic.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | #include "clipperplus/utils.h" 4 | #include "clipperplus/clipperplus_heuristic.h" 5 | 6 | 7 | namespace clipperplus 8 | { 9 | 10 | 11 | std::vector find_heuristic_clique( 12 | const clipperplus::Graph &graph, 13 | int upper_bound, 14 | int lower_bound 15 | ) { 16 | auto kcores = graph.get_core_numbers(); 17 | auto ordered_nodes = graph.get_core_ordering(); 18 | auto max_core_number = graph.max_core_number(); 19 | 20 | std::vector max_clique; 21 | int max_clique_size = lower_bound; 22 | 23 | for(auto it = ordered_nodes.rbegin(); it != ordered_nodes.rend(); ++it) { 24 | auto v = *it; 25 | 26 | if(kcores[v] < max_clique_size) { 27 | continue; 28 | } 29 | 30 | std::vector S; 31 | for(auto u : graph.neighbors(v)) { 32 | if(kcores[u] >= max_clique_size) { 33 | S.push_back(u); 34 | } 35 | } 36 | assert(S.size() >= max_clique_size); 37 | 38 | std::stable_sort(S.begin(), S.end(), [&](Node a, Node b) { 39 | return kcores[a] > kcores[b]; 40 | }); 41 | 42 | std::vector C = { v }; 43 | for(auto u : S) { 44 | auto connected = std::all_of(C.begin(), C.end(), [&](Node v){ 45 | return graph.is_edge(u, v); 46 | }); 47 | 48 | if(connected) { 49 | C.push_back(u); 50 | } 51 | } 52 | 53 | if(C.size() > max_clique_size) { 54 | max_clique_size = C.size(); 55 | max_clique = std::move(C); 56 | } 57 | 58 | if(max_clique_size == upper_bound) { 59 | break; 60 | } 61 | } 62 | 63 | return max_clique; 64 | } 65 | 66 | 67 | int estimate_chormatic_number_welsh_powell(const Graph &graph) 68 | { 69 | std::vector node_color(graph.size(), -1); 70 | auto degrees = graph.degrees(); 71 | 72 | std::vector node_order(graph.size(), 0); 73 | std::iota(node_order.begin(), node_order.end(), 0); 74 | std::sort(node_order.begin(), node_order.end(), [°rees](Node a, Node b) { return degrees[a] > degrees[b]; }); 75 | 76 | int color = 0; 77 | for(auto v : node_order) { 78 | std::set colored; // colored using `color = i` 79 | if(node_color[v] != -1) { 80 | continue; 81 | } 82 | 83 | node_color[v] = color; 84 | colored.insert(v); 85 | 86 | for(auto u : node_order) { 87 | if(u == v || node_color[u] != -1) { 88 | continue; 89 | } 90 | 91 | auto conflicts = std::any_of(colored.begin(), colored.end(), [&](Node v){ 92 | return graph.is_edge(u, v); 93 | }); 94 | 95 | if(!conflicts) { 96 | node_color[u] = color; 97 | colored.insert(u); 98 | } 99 | } 100 | 101 | ++color; 102 | } 103 | 104 | return color; 105 | } 106 | 107 | } 108 | -------------------------------------------------------------------------------- /src/clique_optimization.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | compute core number of graph vertices, and quickly find a miximal clique. 3 | Code based on Parallel Maximum Clique Algorithm by Ryan A. Rossi (http://ryanrossi.com/pmc) 4 | 5 | Author: kaveh fathian (kavehfathian@gmail.com) 6 | */ 7 | 8 | #include "clipperplus/clique_optimization.h" 9 | 10 | namespace clipperplus 11 | { 12 | 13 | std::vector clique_optimization( 14 | const Eigen::MatrixXd &_M, 15 | const Eigen::VectorXd &u0, 16 | const Params ¶ms) 17 | { 18 | const auto t_start = std::chrono::high_resolution_clock::now(); 19 | 20 | // Initialization 21 | const size_t n = _M.cols(); 22 | const Eigen::MatrixXd C = _M; 23 | 24 | // Zero out any entry corresponding to an active constraint 25 | const Eigen::MatrixXd M = _M.cwiseProduct(C); 26 | 27 | // Binary complement of constraint matrix 28 | const Eigen::MatrixXd Cb = Eigen::MatrixXd::Ones(n, n) - C; 29 | 30 | // one step of power method to have a good scaling of u 31 | Eigen::VectorXd u = M * u0; 32 | u.normalize(); 33 | 34 | // initial value of d 35 | double d = 0; // zero if there are no active constraints 36 | Eigen::MatrixXd Cbu = Cb * u; 37 | Eigen::MatrixXd Mu = M * u; 38 | auto num = Eigen::VectorXd(n); 39 | auto den = Eigen::VectorXd(n); 40 | Eigen::VectorXi idxD = ((Cbu.array() > params.eps) && (u.array() > params.eps)).cast(); 41 | if (idxD.sum() > 0) 42 | { 43 | num = utils::selectFromIndicator(Mu, idxD); 44 | den = utils::selectFromIndicator(Cbu, idxD); 45 | d = (num.array() / den.array()).minCoeff(); 46 | } 47 | 48 | auto Md = Eigen::MatrixXd(M.rows(), M.cols()); 49 | Md = M - d * Cb; 50 | 51 | #ifdef DEBUG_TIMING 52 | const auto t2 = std::chrono::high_resolution_clock::now(); // timer 53 | auto dur = std::chrono::duration_cast(t2 - t_start); 54 | auto elaps = static_cast(dur.count()) / 1e6; 55 | std::cout << "clipper time: u0, d set up: " << elaps << std::endl; 56 | #endif 57 | #ifdef DEBUG_OPTIM 58 | std::cout << "clipper: u0: "; 59 | for (int ii = 0; ii < u0.size(); ++ii) 60 | { 61 | std::cout << u0(ii) << " "; 62 | } 63 | std::cout << std::endl; 64 | std::cout << "clipper: u: "; 65 | for (int ii = 0; ii < u.size(); ++ii) 66 | { 67 | std::cout << u(ii) << " "; 68 | } 69 | std::cout << std::endl; 70 | std::cout << "clipper: initial d: " << d << std::endl; 71 | 72 | std::cout << "clipper: params.tol_u: " << params.tol_u << std::endl; 73 | std::cout << "clipper: params.tol_F: " << params.tol_F << std::endl; 74 | std::cout << "clipper: params.eps: " << params.eps << std::endl; 75 | std::cout << "clipper: params.maxlsiters: " << params.maxlsiters << std::endl; 76 | #endif 77 | 78 | // initialize memory 79 | auto gradF = Eigen::VectorXd(n); 80 | auto gradFnew = Eigen::VectorXd(n); 81 | auto unew = Eigen::VectorXd(n); 82 | 83 | // Orthogonal projected gradient ascent 84 | double F = 0; // objective value 85 | size_t i; 86 | size_t k; // iteration counters 87 | size_t jsum = 0; 88 | size_t ksum = 0; // total iteration counters 89 | double alpha = 1; // initialize 90 | for (i = 0; i < params.maxoliters; ++i) 91 | { // outerloop 92 | gradF = Md * u; 93 | F = u.dot(gradF); // current objective value 94 | gradF = gradF - F * u; // orthogonal projection of gradient onto tangent plane to S^n at u 95 | 96 | // Orthogonal projected gradient ascent 97 | for (size_t j = 0; j < params.maxiniters; ++j) 98 | { // innerloop 99 | // Backtracking line search on gradient ascent 100 | double Fnew = 0; 101 | double deltaF = 0; 102 | for (k = 0; k < params.maxlsiters; ++k) 103 | { // line search 104 | unew = u + alpha * gradF; // gradient step 105 | unew = unew.cwiseMax(0); // project onto positive orthant 106 | unew.normalize(); // project onto S^n 107 | gradFnew = Md * unew; // new gradient 108 | Fnew = unew.dot(gradFnew); // new objective value after step 109 | 110 | gradFnew = gradFnew - Fnew * unew; // project gradient onto S^n 111 | 112 | deltaF = Fnew - F; // change in objective value 113 | 114 | // armijo condition 115 | bool armijo_cond = (deltaF >= params.sigma * gradF.dot(unew - u)); 116 | if (!armijo_cond) 117 | { 118 | alpha = alpha * params.beta; // backtrack & reduce step size 119 | } 120 | else 121 | { 122 | alpha = alpha / sqrt(params.beta); // increase step size 123 | break; // stop line search 124 | } 125 | ksum++; 126 | 127 | #ifdef DEBUG_OPTIM 128 | if (k == params.maxlsiters - 1) 129 | { 130 | std::cout << "clipper: reached max line search itr." << std::endl; 131 | } 132 | #endif 133 | } // line search 134 | 135 | // chech alpha after line search 136 | if (alpha < params.minalpha) 137 | { // alpha decreased too much 138 | alpha = params.minalpha; 139 | #ifdef DEBUG_OPTIM 140 | std::cout << "lower bounded alpha to min threshold" << std::endl; 141 | #endif 142 | } 143 | else if (alpha > params.maxalpha) 144 | { // alpha increased too much 145 | alpha = params.maxalpha; 146 | #ifdef DEBUG_OPTIM 147 | std::cout << "upper bounded alpha to max threshold" << std::endl; 148 | #endif 149 | } 150 | 151 | const double deltau = (unew - u).norm(); // change in vector u 152 | 153 | // update values 154 | u = unew; 155 | F = Fnew; 156 | gradF = gradFnew; 157 | 158 | // check if desired accuracy has been reached by gradient ascent 159 | if (deltau < params.tol_u || std::abs(deltaF) < params.tol_F) 160 | break; 161 | jsum++; 162 | } // innerloop 163 | 164 | // Increase d 165 | Cbu = Cb * u; 166 | idxD = ((Cbu.array() > params.eps) && (u.array() > params.eps)).cast(); 167 | if (idxD.sum() > 0) 168 | { 169 | Mu = M * u; 170 | num = utils::selectFromIndicator(Mu, idxD); 171 | den = utils::selectFromIndicator(Cbu, idxD); 172 | const double deltad = (num.array() / den.array()).abs().minCoeff(); 173 | 174 | d += deltad; 175 | Md = M - d * Cb; // update Md 176 | } 177 | else 178 | { 179 | break; 180 | } 181 | } // outerloop 182 | 183 | #ifdef DEBUG_TIMING 184 | const auto t3 = std::chrono::high_resolution_clock::now(); // timer 185 | dur = std::chrono::duration_cast(t3 - t2); 186 | elaps = static_cast(dur.count()) / 1e6; 187 | std::cout << "clipper time: optimization: " << elaps << std::endl; 188 | std::cout << "d: " << d << std::endl; 189 | std::cout << "ksum: " << ksum << std::endl; 190 | std::cout << "jsum: " << jsum << std::endl; 191 | std::cout << "i: " << i << std::endl; 192 | #endif 193 | #ifdef DEBUG_OPTIM 194 | std::cout << "clipper: u final: "; 195 | for (int ii = 0; ii < u.size(); ++ii) 196 | { 197 | std::cout << u(ii) << " "; 198 | } 199 | std::cout << std::endl; 200 | #endif 201 | 202 | // Generate output 203 | std::vector nodes; // node indices of rounded u vector 204 | 205 | // pick a rounding threshold between min and max element 206 | const double rounding_thresh = params.eps; 207 | #ifdef DEBUG_OPTIM 208 | std::cout << "clipper: rounding_thresh: " << rounding_thresh << std::endl; 209 | #endif 210 | 211 | nodes = utils::findIndicesWhereAboveThreshold(u, rounding_thresh); 212 | 213 | #ifdef DEBUG_OPTIM 214 | std::cout << "clipper: nodes above eps thresh: "; 215 | for (long i : nodes) 216 | { 217 | std::cout << i << " "; 218 | } 219 | std::cout << std::endl; 220 | #endif 221 | #ifdef DEBUG_TIMING 222 | const auto t4 = std::chrono::high_resolution_clock::now(); // timer 223 | dur = std::chrono::duration_cast(t4 - t3); 224 | elaps = static_cast(dur.count()) / 1e6; 225 | std::cout << "clipper time: rounding output: " << elaps << std::endl; 226 | #endif 227 | 228 | const auto t_end = std::chrono::high_resolution_clock::now(); 229 | const auto duration = std::chrono::duration_cast(t_end - t_start); 230 | const double elapsed = static_cast(duration.count()) / 1e6; 231 | 232 | return nodes; 233 | } 234 | 235 | } 236 | -------------------------------------------------------------------------------- /src/utils.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "clipperplus/utils.h" 3 | 4 | namespace clipperplus::utils 5 | { 6 | 7 | Eigen::VectorXd selectFromIndicator( 8 | const Eigen::VectorXd &x, 9 | const Eigen::VectorXi &ind) 10 | { 11 | Eigen::VectorXd y(ind.sum()); 12 | size_t idx = 0; 13 | for (size_t i = 0; i < x.size(); ++i) 14 | { 15 | if (ind[i]) 16 | { 17 | y[idx] = x[i]; 18 | idx++; 19 | } 20 | } 21 | return y; 22 | } 23 | 24 | std::vector findIndicesWhereAboveThreshold( 25 | const Eigen::VectorXd& x, 26 | double thr 27 | ) { 28 | std::vector indices; 29 | indices.reserve(x.size()); 30 | for (size_t i=0; i thr) indices.push_back(i); 32 | } 33 | return indices; 34 | } 35 | 36 | 37 | } -------------------------------------------------------------------------------- /test/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | include(GoogleTest) 2 | 3 | add_executable(tests main.cpp clipperplus_test.cpp) 4 | target_link_libraries(tests clipperplus gtest pthread Eigen3::Eigen) 5 | gtest_add_tests(TARGET tests TEST_LIST all_tests) 6 | set_tests_properties(${all_tests} PROPERTIES TIMEOUT 10) -------------------------------------------------------------------------------- /test/clipperplus_test.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | c++ tests for clipper+ library 3 | */ 4 | 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | 11 | // for computating core numbers and PMC-heuristic clique 12 | #include "clipperplus/clipperplus_clique.h" 13 | 14 | 15 | TEST(CLIPPERPLUS, clique1) 16 | { 17 | std::cout << "adjacency matrix 1:\n" << std::endl; 18 | 19 | Eigen::MatrixXd adj(10,10); // graph affinity matrix 20 | adj << 0, 0, 1, 1, 1, 1, 1, 0, 1, 0, 21 | 0, 0, 1, 1, 1, 0, 1, 1, 1, 1, 22 | 1, 1, 0, 1, 0, 1, 1, 1, 0, 1, 23 | 1, 1, 1, 0, 1, 1, 1, 1, 1, 1, 24 | 1, 1, 0, 1, 0, 0, 1, 1, 1, 1, 25 | 1, 0, 1, 1, 0, 0, 1, 1, 1, 1, 26 | 1, 1, 1, 1, 1, 1, 0, 1, 1, 0, 27 | 0, 1, 1, 1, 1, 1, 1, 0, 1, 1, 28 | 1, 1, 0, 1, 1, 1, 1, 1, 0, 1, 29 | 0, 1, 1, 1, 1, 1, 0, 1, 1, 0; 30 | 31 | std::cout << adj << "\n" << std::endl; 32 | 33 | auto [clique, certificate] = clipperplus::find_clique(adj); 34 | std::sort(clique.begin(), clique.end()); 35 | 36 | EXPECT_EQ(clique.size(), 6); 37 | decltype(clique) clique_expected = {1, 3, 4, 6, 7, 8}; 38 | EXPECT_EQ(clique, clique_expected); 39 | EXPECT_EQ(certificate, clipperplus::CERTIFICATE::NONE); 40 | 41 | // in this case we have two equal maximum cliques and it fails!! 42 | // one should update the test-case 43 | }; 44 | 45 | TEST(CLIPPERPLUS, clique2) { 46 | std::cout << "adjacency matrix 2: \n" << std::endl; 47 | 48 | Eigen::MatrixXd adj(10,10); // graph affinity matrix 49 | adj << 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 50 | 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 51 | 1, 1, 0, 1, 1, 1, 1, 1, 1, 1, 52 | 1, 1, 1, 0, 1, 1, 1, 0, 1, 1, 53 | 1, 1, 1, 1, 0, 1, 0, 1, 1, 0, 54 | 1, 1, 1, 1, 1, 0, 1, 1, 1, 1, 55 | 1, 1, 1, 1, 0, 1, 0, 1, 1, 1, 56 | 1, 1, 1, 0, 1, 1, 1, 0, 1, 1, 57 | 1, 1, 1, 1, 1, 1, 1, 1, 0, 1, 58 | 1, 1, 1, 1, 0, 1, 1, 1, 1, 0; 59 | 60 | std::cout << adj << "\n" << std::endl; 61 | 62 | auto [clique, certificate] = clipperplus::find_clique(adj); 63 | std::sort(clique.begin(), clique.end()); 64 | 65 | EXPECT_EQ(clique.size(), 7); 66 | decltype(clique) clique_expected = {0, 2, 3, 5, 6, 8, 9}; 67 | EXPECT_EQ(clique, clique_expected); 68 | EXPECT_EQ(certificate, clipperplus::CERTIFICATE::CHROMATIC_BOUND); 69 | }; 70 | 71 | TEST(CLIPPERPLUS, clique3) { 72 | std::cout << "adjacency matrix 3: \n" << std::endl; 73 | 74 | Eigen::MatrixXd adj(20,20); // graph affinity matrix 75 | adj << 0, 0, 1, 0, 0, 1, 1, 1, 0, 0, 1, 1, 0, 1, 1, 1, 1, 1, 0, 1, 76 | 0, 0, 1, 1, 1, 1, 1, 1, 0, 1, 1, 1, 1, 1, 1, 0, 1, 0, 1, 1, 77 | 1, 1, 0, 1, 0, 1, 0, 1, 1, 1, 0, 1, 1, 0, 0, 1, 1, 1, 1, 0, 78 | 0, 1, 1, 0, 0, 1, 1, 1, 1, 0, 1, 0, 1, 1, 1, 0, 1, 1, 1, 1, 79 | 0, 1, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 80 | 1, 1, 1, 1, 0, 0, 1, 0, 1, 0, 1, 1, 1, 0, 0, 1, 1, 1, 1, 1, 81 | 1, 1, 0, 1, 1, 1, 0, 1, 1, 0, 1, 1, 1, 1, 0, 1, 1, 1, 1, 1, 82 | 1, 1, 1, 1, 1, 0, 1, 0, 1, 0, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 83 | 0, 0, 1, 1, 1, 1, 1, 1, 0, 1, 1, 1, 0, 1, 1, 1, 1, 0, 1, 0, 84 | 0, 1, 1, 0, 1, 0, 0, 0, 1, 0, 1, 1, 0, 0, 1, 1, 0, 0, 1, 1, 85 | 1, 1, 0, 1, 1, 1, 1, 1, 1, 1, 0, 1, 0, 1, 1, 1, 1, 1, 1, 1, 86 | 1, 1, 1, 0, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 1, 1, 0, 1, 1, 1, 87 | 0, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 1, 1, 0, 1, 1, 1, 88 | 1, 1, 0, 1, 1, 0, 1, 1, 1, 0, 1, 0, 0, 0, 1, 1, 1, 1, 1, 1, 89 | 1, 1, 0, 1, 1, 0, 0, 1, 1, 1, 1, 1, 1, 1, 0, 1, 1, 1, 1, 1, 90 | 1, 0, 1, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 1, 1, 1, 0, 91 | 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 1, 0, 0, 1, 1, 1, 0, 1, 1, 0, 92 | 1, 0, 1, 1, 1, 1, 1, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 0, 1, 1, 93 | 0, 1, 1, 1, 1, 1, 1, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 1, 94 | 1, 1, 0, 1, 1, 1, 1, 0, 0, 1, 1, 1, 1, 1, 1, 0, 0, 1, 1, 0; 95 | 96 | std::cout << adj << "\n" << std::endl; 97 | 98 | auto [clique, certificate] = clipperplus::find_clique(adj); 99 | std::sort(clique.begin(), clique.end()); 100 | 101 | EXPECT_EQ(clique.size(), 8); 102 | decltype(clique) clique_expected = {4, 10, 13, 14, 15, 16, 17, 18}; 103 | EXPECT_EQ(clique, clique_expected); 104 | EXPECT_EQ(certificate, clipperplus::CERTIFICATE::NONE); 105 | }; 106 | 107 | 108 | TEST(CLIPPERPLUS, clique4) { 109 | std::cout << "adjacency matrix 1:\n" << std::endl; 110 | 111 | Eigen::MatrixXd adj(5, 5); // graph affinity matrix 112 | adj << 0, 1, 1, 0, 0, 113 | 1, 0, 1, 0, 0, 114 | 1, 1, 0, 0, 0, 115 | 0, 0, 0, 0, 1, 116 | 0, 0, 0, 1, 0; 117 | 118 | std::cout << adj << "\n" << std::endl; 119 | 120 | auto [clique, certificate] = clipperplus::find_clique(adj); 121 | std::sort(clique.begin(), clique.end()); 122 | 123 | EXPECT_EQ(clique.size(), 3); 124 | decltype(clique) clique_expected = {0, 1, 2}; 125 | EXPECT_EQ(clique, clique_expected); 126 | EXPECT_EQ(certificate, clipperplus::CERTIFICATE::HEURISTIC); 127 | }; 128 | -------------------------------------------------------------------------------- /test/data/bun10k.ply: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ariarobotics/clipperp/a524943411bf6635219ab510864c81aa1b6a0c7a/test/data/bun10k.ply -------------------------------------------------------------------------------- /test/main.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | int main(int argc, char** argv) { 4 | testing::InitGoogleTest(&argc, argv); 5 | return RUN_ALL_TESTS(); 6 | } -------------------------------------------------------------------------------- /test/matlab/DIMACS9.mat: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ariarobotics/clipperp/a524943411bf6635219ab510864c81aa1b6a0c7a/test/matlab/DIMACS9.mat -------------------------------------------------------------------------------- /test/matlab/test_clique.m: -------------------------------------------------------------------------------- 1 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 2 | % CLIPPER+ clique test: finds a maximal clique in a given graph, and 3 | % certify if it's the maximum clique 4 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 5 | clear all; 6 | close all; 7 | clc; 8 | 9 | addpath(genpath('../../build/bindings/matlab')) % clipper+ mex file 10 | %% 11 | 12 | % graph adjacency matrix 13 | adj = [ 0, 0, 1, 1, 1; 14 | 0, 0, 1, 1, 1; 15 | 1, 1, 0, 1, 1; 16 | 1, 1, 1, 0, 1; 17 | 1, 1, 1, 1, 0]; 18 | 19 | % run clipper+ clique finding algorithm 20 | [clique_size, clique, certificate, runtime] = clipperplus_clique_mex(adj) 21 | -------------------------------------------------------------------------------- /test/matlab/test_dimacs.m: -------------------------------------------------------------------------------- 1 | %% test CLIPPER+ maximal clique on DIMACS graph dataset 2 | % 3 | % THE SECOND DIMACS IMPLEMENTAION CHALENGE (1992-1993) 4 | % https://iridia.ulb.ac.be/~fmascia/maximum_clique/DIMACS-benchmark 5 | % 6 | 7 | clear all; 8 | close all; 9 | clc; 10 | 11 | addpath(genpath('../../build/bindings/matlab')) % clipper+ mex file 12 | 13 | %% load dataset 14 | 15 | Ms = load('DIMACS9.mat'); 16 | 17 | names = {'M_p_hat300_1'; 'M_p_hat300_2'; 'M_C1259'; 'M_C2509'; ... 18 | 'M_keller4'; 'M_p_hat300_2'; 'M_brock200_4'; ... 19 | 'M_brock200_2'; 'M_gen200_p09_44'; 'M_gen200_p09_55'}; % graphs in DIMACS dataset 20 | omega_gt = [8; 25; 34; 44; 11; 25; 17; 12; 44; 55]; % ground truth clique size 21 | 22 | 23 | %% 24 | 25 | num_graphs = length(names); % number of graphs 26 | 27 | omega_ratio = zeros(num_graphs, 1); 28 | runtime = zeros(num_graphs, 1); 29 | density = zeros(num_graphs, 1); 30 | certificates = zeros(num_graphs, 1); 31 | 32 | for graph = 1 : num_graphs 33 | M = Ms.(names{graph}); % matrix M for this benchmark 34 | n = length(M); % nodes 35 | adj = M - eye(n); % adjacency matrix 36 | 37 | fprintf('processing graph %s ...\n', names{graph}); 38 | 39 | density(graph) = nnz(adj) / (n*(n-1)); 40 | fprintf('graph density = %g \n', density(graph)); 41 | 42 | fprintf('benchmarking clipper+_clique\n'); 43 | [omega_hat, clique_idx, certificate, t] = clipperplus_clique_mex(adj); 44 | omega_ratio(graph, 1) = omega_hat/omega_gt(graph); % max clique ratio at this run 45 | certificates(graph,1) = certificate; 46 | runtime(graph, 1) = t; 47 | 48 | fprintf('\n\n'); 49 | end % end for 50 | 51 | 52 | %% display results 53 | 54 | or_clipper_plus = omega_ratio(:,1); 55 | 56 | th = table(names, density, omega_gt, ... 57 | or_clipper_plus, runtime, certificates) 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | -------------------------------------------------------------------------------- /test/python/ex0_test.ipynb: -------------------------------------------------------------------------------- 1 | { 2 | "cells": [ 3 | { 4 | "cell_type": "markdown", 5 | "metadata": {}, 6 | "source": [ 7 | "# Basic Clipperplus Tests" 8 | ] 9 | }, 10 | { 11 | "cell_type": "code", 12 | "execution_count": null, 13 | "metadata": {}, 14 | "outputs": [], 15 | "source": [ 16 | "import numpy as np\n", 17 | "import clipperpluspy\n", 18 | "import unittest" 19 | ] 20 | }, 21 | { 22 | "cell_type": "code", 23 | "execution_count": null, 24 | "metadata": {}, 25 | "outputs": [], 26 | "source": [ 27 | "class TestClipperplus(unittest.TestCase):\n", 28 | " \n", 29 | " test_data = [\n", 30 | " {\"name\": \"Adjacency Matrix 1\",\n", 31 | " \"adj\": np.array([[0, 0, 1, 1, 1, 1, 1, 0, 1, 0],\n", 32 | " [0, 0, 1, 1, 1, 0, 1, 1, 1, 1],\n", 33 | " [1, 1, 0, 1, 0, 1, 1, 1, 0, 1],\n", 34 | " [1, 1, 1, 0, 1, 1, 1, 1, 1, 1],\n", 35 | " [1, 1, 0, 1, 0, 0, 1, 1, 1, 1],\n", 36 | " [1, 0, 1, 1, 0, 0, 1, 1, 1, 1],\n", 37 | " [1, 1, 1, 1, 1, 1, 0, 1, 1, 0],\n", 38 | " [0, 1, 1, 1, 1, 1, 1, 0, 1, 1],\n", 39 | " [1, 1, 0, 1, 1, 1, 1, 1, 0, 1],\n", 40 | " [0, 1, 1, 1, 1, 1, 0, 1, 1, 0]]),\n", 41 | " \"expected_clique_size\": 6,\n", 42 | " \"expected_clique\": [1, 3, 4, 6, 7, 8],\n", 43 | " \"expected_certificate\": 0},\n", 44 | " {\"name\": \"Adjacency Matrix 2\",\n", 45 | " \"adj\": np.array([[0, 0, 1, 1, 1, 1, 1, 1, 1, 1],\n", 46 | " [0, 0, 1, 1, 1, 1, 1, 1, 1, 1],\n", 47 | " [1, 1, 0, 1, 1, 1, 1, 1, 1, 1],\n", 48 | " [1, 1, 1, 0, 1, 1, 1, 0, 1, 1],\n", 49 | " [1, 1, 1, 1, 0, 1, 0, 1, 1, 0],\n", 50 | " [1, 1, 1, 1, 1, 0, 1, 1, 1, 1],\n", 51 | " [1, 1, 1, 1, 0, 1, 0, 1, 1, 1],\n", 52 | " [1, 1, 1, 0, 1, 1, 1, 0, 1, 1],\n", 53 | " [1, 1, 1, 1, 1, 1, 1, 1, 0, 1],\n", 54 | " [1, 1, 1, 1, 0, 1, 1, 1, 1, 0]]),\n", 55 | " \"expected_clique_size\": 7,\n", 56 | " \"expected_clique\": [6, 0, 2, 3, 5, 8, 9],\n", 57 | " \"expected_certificate\": 3},\n", 58 | " {\"name\": \"Adjacency Matrix 3\",\n", 59 | " \"adj\": np.array([[0, 0, 1, 0, 0, 1, 1, 1, 0, 0, 1, 1, 0, 1, 1, 1, 1, 1, 0, 1],\n", 60 | " [0, 0, 1, 1, 1, 1, 1, 1, 0, 1, 1, 1, 1, 1, 1, 0, 1, 0, 1, 1],\n", 61 | " [1, 1, 0, 1, 0, 1, 0, 1, 1, 1, 0, 1, 1, 0, 0, 1, 1, 1, 1, 0],\n", 62 | " [0, 1, 1, 0, 0, 1, 1, 1, 1, 0, 1, 0, 1, 1, 1, 0, 1, 1, 1, 1],\n", 63 | " [0, 1, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1],\n", 64 | " [1, 1, 1, 1, 0, 0, 1, 0, 1, 0, 1, 1, 1, 0, 0, 1, 1, 1, 1, 1],\n", 65 | " [1, 1, 0, 1, 1, 1, 0, 1, 1, 0, 1, 1, 1, 1, 0, 1, 1, 1, 1, 1],\n", 66 | " [1, 1, 1, 1, 1, 0, 1, 0, 1, 0, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0],\n", 67 | " [0, 0, 1, 1, 1, 1, 1, 1, 0, 1, 1, 1, 0, 1, 1, 1, 1, 0, 1, 0],\n", 68 | " [0, 1, 1, 0, 1, 0, 0, 0, 1, 0, 1, 1, 0, 0, 1, 1, 0, 0, 1, 1],\n", 69 | " [1, 1, 0, 1, 1, 1, 1, 1, 1, 1, 0, 1, 0, 1, 1, 1, 1, 1, 1, 1],\n", 70 | " [1, 1, 1, 0, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 1, 1, 0, 1, 1, 1],\n", 71 | " [0, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 1, 1, 0, 1, 1, 1],\n", 72 | " [1, 1, 0, 1, 1, 0, 1, 1, 1, 0, 1, 0, 0, 0, 1, 1, 1, 1, 1, 1],\n", 73 | " [1, 1, 0, 1, 1, 0, 0, 1, 1, 1, 1, 1, 1, 1, 0, 1, 1, 1, 1, 1],\n", 74 | " [1, 0, 1, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 1, 1, 1, 0],\n", 75 | " [1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 1, 0, 0, 1, 1, 1, 0, 1, 1, 0],\n", 76 | " [1, 0, 1, 1, 1, 1, 1, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 0, 1, 1],\n", 77 | " [0, 1, 1, 1, 1, 1, 1, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 1],\n", 78 | " [1, 1, 0, 1, 1, 1, 1, 0, 0, 1, 1, 1, 1, 1, 1, 0, 0, 1, 1, 0]]),\n", 79 | " \"expected_clique_size\": 8,\n", 80 | " \"expected_clique\": [4, 10, 13, 14, 15, 16, 17, 18],\n", 81 | " \"expected_certificate\": 0}\n", 82 | " ]\n", 83 | " def test_clique(self):\n", 84 | " for i in range(len(self.test_data)):\n", 85 | " with self.subTest(\"Finding cliques on predetermined adjacency matrices\", i=i):\n", 86 | " adj = self.test_data[i][\"adj\"]\n", 87 | " clique_size, clique, certificate = clipperpluspy.clipperplus_clique(adj)\n", 88 | " print(f\"\\nTest {i}: {self.test_data[i]['name']}\\n\")\n", 89 | " print(f\"{self.test_data[i]['adj']}\\n\", flush=True)\n", 90 | " self.assertEqual(clique_size, self.test_data[i][\"expected_clique_size\"])\n", 91 | " self.assertEqual(clique, self.test_data[i][\"expected_clique\"])\n", 92 | " self.assertEqual(certificate, self.test_data[i][\"expected_certificate\"])\n", 93 | " print(flush=True)" 94 | ] 95 | }, 96 | { 97 | "cell_type": "code", 98 | "execution_count": null, 99 | "metadata": {}, 100 | "outputs": [], 101 | "source": [ 102 | "unittest.main(argv=[''], verbosity=2, exit=False)" 103 | ] 104 | } 105 | ], 106 | "metadata": { 107 | "kernelspec": { 108 | "display_name": "Python 3", 109 | "language": "python", 110 | "name": "python3" 111 | }, 112 | "language_info": { 113 | "codemirror_mode": { 114 | "name": "ipython", 115 | "version": 3 116 | }, 117 | "file_extension": ".py", 118 | "mimetype": "text/x-python", 119 | "name": "python", 120 | "nbconvert_exporter": "python", 121 | "pygments_lexer": "ipython3", 122 | "version": "3.10.6" 123 | } 124 | }, 125 | "nbformat": 4, 126 | "nbformat_minor": 2 127 | } 128 | --------------------------------------------------------------------------------